1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-25 01:05:27 +03:00

Add GPS coordinates OSD elements display variants; add support for Open Location Code display

Adds variations in GPS coordinate OSD element display:
1. Fractional degrees with 7 digits (default) - 000.0000000
2. Fractional degrees with 4 digits - 000.0000
3. Degrees, minutes, seconds - 000^00'00.0"E
4. Open Location Code (sometimed called Google Plus Code) - 23ABC4R8+M37

Uses Open Location Code library from:
https://github.com/google/open-location-code

Added support for `STATE(GPS_FIX_EVER)` to differentiate from having a fix now (`STATE(GPS_FIX)`) vs. ever having a fix.

Logic change to only display coordinates from the GPS module once a fix has been initially established. This prevents displaying interim coordinates supplied by the GPS while the fix is still being establised as these coordinates can be inaccurate by hundreds of miles. Once a fix is established initially then the coordinates will continue to be displayed even if the fix is lost or degrades in quality.

Add logic to "blink" the coordinates if the 3D fix is lost after initially being established. Alerts the user that the coordinate display may be inaccurate or no longer being updated. We want to keep the coordinates displayed to aid recovery if the user loses the fix (like crashing upside down).

Replace GPS defines `LAT` and `LON` used throughout the code with the enumeration:
```
typedef enum {
    GPS_LATITUDE,
    GPS_LONGITUDE
} gpsCoordinateType_e;
```

The Open Location Code option is bounded with `USE_GPS_PLUS_CODE` to allow it to be excluded if needed for targets with limited flash space. It currently fits for F411 but we may have to remove it in the future.
This commit is contained in:
Bruce Luckcuck 2021-02-16 19:40:12 -05:00 committed by mikeller
parent 8511ba930f
commit 37dbbd0755
20 changed files with 1240 additions and 66 deletions

View file

@ -1035,15 +1035,15 @@ static void writeGPSFrame(timeUs_t currentTimeUs)
}
blackboxWriteUnsignedVB(gpsSol.numSat);
blackboxWriteSignedVB(gpsSol.llh.lat - gpsHistory.GPS_home[LAT]);
blackboxWriteSignedVB(gpsSol.llh.lon - gpsHistory.GPS_home[LON]);
blackboxWriteSignedVB(gpsSol.llh.lat - gpsHistory.GPS_home[GPS_LATITUDE]);
blackboxWriteSignedVB(gpsSol.llh.lon - gpsHistory.GPS_home[GPS_LONGITUDE]);
blackboxWriteUnsignedVB(gpsSol.llh.altCm / 10); // was originally designed to transport meters in int16, but +-3276.7m is a good compromise
blackboxWriteUnsignedVB(gpsSol.groundSpeed);
blackboxWriteUnsignedVB(gpsSol.groundCourse);
gpsHistory.GPS_numSat = gpsSol.numSat;
gpsHistory.GPS_coord[LAT] = gpsSol.llh.lat;
gpsHistory.GPS_coord[LON] = gpsSol.llh.lon;
gpsHistory.GPS_coord[GPS_LATITUDE] = gpsSol.llh.lat;
gpsHistory.GPS_coord[GPS_LONGITUDE] = gpsSol.llh.lon;
}
#endif
@ -1637,8 +1637,8 @@ STATIC_UNIT_TESTED void blackboxLogIteration(timeUs_t currentTimeUs)
writeGPSHomeFrame();
writeGPSFrame(currentTimeUs);
} else if (gpsSol.numSat != gpsHistory.GPS_numSat
|| gpsSol.llh.lat != gpsHistory.GPS_coord[LAT]
|| gpsSol.llh.lon != gpsHistory.GPS_coord[LON]) {
|| gpsSol.llh.lat != gpsHistory.GPS_coord[GPS_LATITUDE]
|| gpsSol.llh.lon != gpsHistory.GPS_coord[GPS_LONGITUDE]) {
//We could check for velocity changes as well but I doubt it changes independent of position
writeGPSFrame(currentTimeUs);
}

View file

@ -156,3 +156,8 @@
#define SYM_STICK_OVERLAY_CENTER 0x0B
#define SYM_STICK_OVERLAY_VERTICAL 0x16
#define SYM_STICK_OVERLAY_HORIZONTAL 0x17
// GPS degree/minute/second symbols
#define SYM_GPS_DEGREE SYM_STICK_OVERLAY_SPRITE_HIGH // kind of looks like the degree symbol
#define SYM_GPS_MINUTE 0x27 // '
#define SYM_GPS_SECOND 0x22 // "

View file

@ -114,6 +114,7 @@ extern uint16_t flightModeFlags;
typedef enum {
GPS_FIX_HOME = (1 << 0),
GPS_FIX = (1 << 1),
GPS_FIX_EVER = (1 << 2),
} stateFlags_t;
#define DISABLE_STATE(mask) (stateFlags &= ~(mask))

View file

@ -950,11 +950,7 @@ static bool gpsNewFrameNMEA(char c)
gps_Msg.longitude *= -1;
break;
case 6:
if (string[0] > '0') {
ENABLE_STATE(GPS_FIX);
} else {
DISABLE_STATE(GPS_FIX);
}
gpsSetFixState(string[0] > '0');
break;
case 7:
gps_Msg.numSat = grab_fields(string, 0);
@ -1277,11 +1273,7 @@ static bool UBLOX_parse_gps(void)
gpsSol.llh.lon = _buffer.posllh.longitude;
gpsSol.llh.lat = _buffer.posllh.latitude;
gpsSol.llh.altCm = _buffer.posllh.altitudeMslMm / 10; //alt in cm
if (next_fix) {
ENABLE_STATE(GPS_FIX);
} else {
DISABLE_STATE(GPS_FIX);
}
gpsSetFixState(next_fix);
_new_position = true;
break;
case MSG_STATUS:
@ -1499,7 +1491,7 @@ static void GPS_calculateDistanceFlownVerticalSpeed(bool initialize)
if (speed > GPS_DISTANCE_FLOWN_MIN_SPEED_THRESHOLD_CM_S) {
uint32_t dist;
int32_t dir;
GPS_distance_cm_bearing(&gpsSol.llh.lat, &gpsSol.llh.lon, &lastCoord[LAT], &lastCoord[LON], &dist, &dir);
GPS_distance_cm_bearing(&gpsSol.llh.lat, &gpsSol.llh.lon, &lastCoord[GPS_LATITUDE], &lastCoord[GPS_LONGITUDE], &dist, &dir);
if (gpsConfig()->gps_use_3d_speed) {
dist = sqrtf(powf(gpsSol.llh.altCm - lastAlt, 2.0f) + powf(dist, 2.0f));
}
@ -1509,8 +1501,8 @@ static void GPS_calculateDistanceFlownVerticalSpeed(bool initialize)
GPS_verticalSpeedInCmS = (gpsSol.llh.altCm - lastAlt) * 1000 / (currentMillis - lastMillis);
GPS_verticalSpeedInCmS = constrain(GPS_verticalSpeedInCmS, -1500, 1500);
}
lastCoord[LON] = gpsSol.llh.lon;
lastCoord[LAT] = gpsSol.llh.lat;
lastCoord[GPS_LONGITUDE] = gpsSol.llh.lon;
lastCoord[GPS_LATITUDE] = gpsSol.llh.lat;
lastAlt = gpsSol.llh.altCm;
lastMillis = currentMillis;
}
@ -1519,8 +1511,8 @@ void GPS_reset_home_position(void)
{
if (!STATE(GPS_FIX_HOME) || !gpsConfig()->gps_set_home_point_once) {
if (STATE(GPS_FIX) && gpsSol.numSat >= 5) {
GPS_home[LAT] = gpsSol.llh.lat;
GPS_home[LON] = gpsSol.llh.lon;
GPS_home[GPS_LATITUDE] = gpsSol.llh.lat;
GPS_home[GPS_LONGITUDE] = gpsSol.llh.lon;
GPS_calc_longitude_scaling(gpsSol.llh.lat); // need an initial value for distance and bearing calc
// Set ground altitude
ENABLE_STATE(GPS_FIX_HOME);
@ -1550,7 +1542,7 @@ void GPS_calculateDistanceAndDirectionToHome(void)
if (STATE(GPS_FIX_HOME)) { // If we don't have home set, do not display anything
uint32_t dist;
int32_t dir;
GPS_distance_cm_bearing(&gpsSol.llh.lat, &gpsSol.llh.lon, &GPS_home[LAT], &GPS_home[LON], &dist, &dir);
GPS_distance_cm_bearing(&gpsSol.llh.lat, &gpsSol.llh.lon, &GPS_home[GPS_LATITUDE], &GPS_home[GPS_LONGITUDE], &dist, &dir);
GPS_distanceToHome = dist / 100;
GPS_directionToHome = dir / 100;
} else {
@ -1585,4 +1577,13 @@ void onGpsNewData(void)
#endif
}
void gpsSetFixState(bool state)
{
if (state) {
ENABLE_STATE(GPS_FIX);
ENABLE_STATE(GPS_FIX_EVER);
} else {
DISABLE_STATE(GPS_FIX);
}
}
#endif

View file

@ -25,13 +25,15 @@
#include "pg/pg.h"
#define LAT 0
#define LON 1
#define GPS_DEGREES_DIVIDER 10000000L
#define GPS_X 1
#define GPS_Y 0
typedef enum {
GPS_LATITUDE,
GPS_LONGITUDE
} gpsCoordinateType_e;
typedef enum {
GPS_NMEA = 0,
GPS_UBLOX,
@ -188,4 +190,4 @@ void onGpsNewData(void);
void GPS_reset_home_position(void);
void GPS_calc_longitude_scaling(int32_t lat);
void GPS_distance_cm_bearing(int32_t *currentLat1, int32_t *currentLon1, int32_t *destinationLat2, int32_t *destinationLon2, uint32_t *dist, int32_t *bearing);
void gpsSetFixState(bool state);

View file

@ -3181,11 +3181,7 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP,
#ifdef USE_GPS
case MSP_SET_RAW_GPS:
if (sbufReadU8(src)) {
ENABLE_STATE(GPS_FIX);
} else {
DISABLE_STATE(GPS_FIX);
}
gpsSetFixState(sbufReadU8(src));
gpsSol.numSat = sbufReadU8(src);
gpsSol.llh.lat = sbufReadU32(src);
gpsSol.llh.lon = sbufReadU32(src);

View file

@ -59,6 +59,45 @@
CLI parameters should be added before line #endif // end of #ifdef USE_OSD
*/
/*
*********************
OSD element variants:
*********************
Each element can have up to 4 display variants. "Type 1" is always the default and every
every element has an implicit type 1 variant even if no additional options exist. The
purpose is to allow the user to choose a different element display or rendering style to
fit their needs. Like displaying GPS coordinates in a different format, displaying a voltage
with a different number of decimal places, etc. The purpose is NOT to display unrelated
information in different variants of the element. For example it would be inappropriate
to use variants to display RSSI for one type and link quality for another. In this case
they should be separate elements. Remember that element variants are mutually exclusive
and only one type can be displayed at a time. So they shouldn't be used in cases where
the user would want to display different types at the same time - like in the above example
where the user might want to display both RSSI and link quality at the same time.
As variants are added to the firmware, support must also be included in the Configurator.
The following lists the variants implemented so far (please update this as variants are added):
OSD_ALTITUDE
type 1: Altitude with one decimal place
type 2: Altitude with no decimal (whole number only)
OSD_GPS_LON
OSD_GPS_LAT
type 1: Decimal representation with 7 digits
type 2: Decimal representation with 4 digits
type 3: Degrees, minutes, seconds
type 4: Open location code (Google Plus Code)
OSD_MAIN_BATT_USAGE
type 1: Graphical bar showing remaining battery (shrinks as used)
type 2: Graphical bar showing battery used (grows as used)
type 3: Numeric % of remaining battery
type 4: Numeric % or used battery
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
@ -122,7 +161,10 @@
#include "sensors/esc_sensor.h"
#include "sensors/sensors.h"
#include "common/maths.h"
#ifdef USE_GPS_PLUS_CODES
// located in lib/main/google/olc
#include "olc.h"
#endif
#define AH_SYMBOL_COUNT 9
#define AH_SIDEBAR_WIDTH_POS 7
@ -273,22 +315,71 @@ static void osdFormatAltitudeString(char * buff, int32_t altitudeCm, osdElementT
}
#ifdef USE_GPS
static void osdFormatCoordinate(char *buff, char sym, int32_t val)
static void osdFormatCoordinate(char *buff, gpsCoordinateType_e coordinateType, osdElementType_e variantType)
{
// latitude maximum integer width is 3 (-90).
// longitude maximum integer width is 4 (-180).
// We show 7 decimals, so we need to use 12 characters:
// eg: s-180.1234567z s=symbol, z=zero terminator, decimal separator between 0 and 1
int32_t gpsValue = 0;
const char leadingSymbol = (coordinateType == GPS_LONGITUDE) ? SYM_LON : SYM_LAT;
// NOTE: Don't use osdPrintFloat() for this. There are too many decimal places and float math doesn't have enough precision
int pos = 0;
buff[pos++] = sym;
if (val < 0) {
buff[pos++] = '-';
val = -val;
if (STATE(GPS_FIX_EVER)) { // don't display interim coordinates until we get the first position fix
gpsValue = (coordinateType == GPS_LONGITUDE) ? gpsSol.llh.lon : gpsSol.llh.lat;
}
const int degreesPart = ABS(gpsValue) / GPS_DEGREES_DIVIDER;
int fractionalPart = ABS(gpsValue) % GPS_DEGREES_DIVIDER;
switch (variantType) {
#ifdef USE_GPS_PLUS_CODES
#define PLUS_CODE_DIGITS 11
case OSD_ELEMENT_TYPE_4: // Open Location Code
{
*buff++ = SYM_SAT_L;
*buff++ = SYM_SAT_R;
if (STATE(GPS_FIX_EVER)) {
OLC_LatLon location;
location.lat = (double)gpsSol.llh.lat / GPS_DEGREES_DIVIDER;
location.lon = (double)gpsSol.llh.lon / GPS_DEGREES_DIVIDER;
OLC_Encode(&location, PLUS_CODE_DIGITS, buff, OSD_ELEMENT_BUFFER_LENGTH - 3);
} else {
memset(buff, SYM_HYPHEN, PLUS_CODE_DIGITS + 1);
buff[8] = '+';
buff[PLUS_CODE_DIGITS + 1] = '\0';
}
break;
}
#endif // USE_GPS_PLUS_CODES
case OSD_ELEMENT_TYPE_3: // degree, minutes, seconds style. ddd^mm'ss.00"W
{
char trailingSymbol;
*buff++ = leadingSymbol;
const int minutes = fractionalPart * 60 / GPS_DEGREES_DIVIDER;
const int fractionalMinutes = fractionalPart * 60 % GPS_DEGREES_DIVIDER;
const int seconds = fractionalMinutes * 60 / GPS_DEGREES_DIVIDER;
const int tenthSeconds = (fractionalMinutes * 60 % GPS_DEGREES_DIVIDER) * 10 / GPS_DEGREES_DIVIDER;
if (coordinateType == GPS_LONGITUDE) {
trailingSymbol = (gpsValue < 0) ? 'W' : 'E';
} else {
trailingSymbol = (gpsValue < 0) ? 'S' : 'N';
}
tfp_sprintf(buff, "%u%c%02u%c%02u.%u%c%c", degreesPart, SYM_GPS_DEGREE, minutes, SYM_GPS_MINUTE, seconds, tenthSeconds, SYM_GPS_SECOND, trailingSymbol);
break;
}
case OSD_ELEMENT_TYPE_2:
fractionalPart /= 1000;
FALLTHROUGH;
case OSD_ELEMENT_TYPE_1:
default:
*buff++ = leadingSymbol;
if (gpsValue < 0) {
*buff++ = SYM_HYPHEN;
}
tfp_sprintf(buff, (variantType == OSD_ELEMENT_TYPE_1 ? "%u.%07u" : "%u.%04u"), degreesPart, fractionalPart);
break;
}
tfp_sprintf(buff + pos, "%d.%07d", val / GPS_DEGREES_DIVIDER, val % GPS_DEGREES_DIVIDER);
}
#endif // USE_GPS
@ -953,14 +1044,15 @@ static void osdElementGpsHomeDistance(osdElementParms_t *element)
}
}
static void osdElementGpsLatitude(osdElementParms_t *element)
static void osdElementGpsCoordinate(osdElementParms_t *element)
{
osdFormatCoordinate(element->buff, SYM_LAT, gpsSol.llh.lat);
}
static void osdElementGpsLongitude(osdElementParms_t *element)
{
osdFormatCoordinate(element->buff, SYM_LON, gpsSol.llh.lon);
const gpsCoordinateType_e coordinateType = (element->item == OSD_GPS_LON) ? GPS_LONGITUDE : GPS_LATITUDE;
osdFormatCoordinate(element->buff, coordinateType, element->type);
if (STATE(GPS_FIX_EVER) && !STATE(GPS_FIX)) {
SET_BLINK(element->item); // blink if we had a fix but have since lost it
} else {
CLR_BLINK(element->item);
}
}
static void osdElementGpsSats(osdElementParms_t *element)
@ -1493,8 +1585,8 @@ const osdElementDrawFn osdElementDrawFunction[OSD_ITEM_COUNT] = {
[OSD_WARNINGS] = osdElementWarnings,
[OSD_AVG_CELL_VOLTAGE] = osdElementAverageCellVoltage,
#ifdef USE_GPS
[OSD_GPS_LON] = osdElementGpsLongitude,
[OSD_GPS_LAT] = osdElementGpsLatitude,
[OSD_GPS_LON] = osdElementGpsCoordinate,
[OSD_GPS_LAT] = osdElementGpsCoordinate,
#endif
[OSD_DEBUG] = osdElementDebug,
#ifdef USE_ACC

View file

@ -409,3 +409,7 @@ extern uint8_t __config_end;
#if defined(USE_RX_SPI) || defined (USE_SERIALRX_SRXL2)
#define USE_RX_BIND
#endif
#ifndef USE_GPS
#undef USE_GPS_PLUS_CODES
#endif

View file

@ -398,4 +398,5 @@
#define USE_RX_MSP_OVERRIDE
#define USE_SIMPLIFIED_TUNING
#define USE_RX_LINK_UPLINK_POWER
#define USE_GPS_PLUS_CODES
#endif

View file

@ -257,15 +257,15 @@ static void GPStoDDDMM_MMMM(int32_t mwiigps, gpsCoordinateDDDMMmmmm_t *result)
static void sendLatLong(int32_t coord[2])
{
gpsCoordinateDDDMMmmmm_t coordinate;
GPStoDDDMM_MMMM(coord[LAT], &coordinate);
GPStoDDDMM_MMMM(coord[GPS_LATITUDE], &coordinate);
frSkyHubWriteFrame(ID_LATITUDE_BP, coordinate.dddmm);
frSkyHubWriteFrame(ID_LATITUDE_AP, coordinate.mmmm);
frSkyHubWriteFrame(ID_N_S, coord[LAT] < 0 ? 'S' : 'N');
frSkyHubWriteFrame(ID_N_S, coord[GPS_LATITUDE] < 0 ? 'S' : 'N');
GPStoDDDMM_MMMM(coord[LON], &coordinate);
GPStoDDDMM_MMMM(coord[GPS_LONGITUDE], &coordinate);
frSkyHubWriteFrame(ID_LONGITUDE_BP, coordinate.dddmm);
frSkyHubWriteFrame(ID_LONGITUDE_AP, coordinate.mmmm);
frSkyHubWriteFrame(ID_E_W, coord[LON] < 0 ? 'W' : 'E');
frSkyHubWriteFrame(ID_E_W, coord[GPS_LONGITUDE] < 0 ? 'W' : 'E');
}
#if defined(USE_GPS)
@ -316,8 +316,8 @@ static void sendFakeLatLong(void)
// Heading is only displayed on OpenTX if non-zero lat/long is also sent
int32_t coord[2] = {0,0};
coord[LAT] = ((0.01f * telemetryConfig()->gpsNoFixLatitude) * GPS_DEGREES_DIVIDER);
coord[LON] = ((0.01f * telemetryConfig()->gpsNoFixLongitude) * GPS_DEGREES_DIVIDER);
coord[GPS_LATITUDE] = ((0.01f * telemetryConfig()->gpsNoFixLatitude) * GPS_DEGREES_DIVIDER);
coord[GPS_LONGITUDE] = ((0.01f * telemetryConfig()->gpsNoFixLongitude) * GPS_DEGREES_DIVIDER);
sendLatLong(coord);
}
@ -330,8 +330,8 @@ static void sendGPSLatLong(void)
if (STATE(GPS_FIX) || gpsFixOccured == 1) {
// If we have ever had a fix, send the last known lat/long
gpsFixOccured = 1;
coord[LAT] = gpsSol.llh.lat;
coord[LON] = gpsSol.llh.lon;
coord[GPS_LATITUDE] = gpsSol.llh.lat;
coord[GPS_LONGITUDE] = gpsSol.llh.lon;
sendLatLong(coord);
} else {
// otherwise send fake lat/long in order to display compass value

View file

@ -213,8 +213,8 @@ static void ltm_oframe(void)
{
ltm_initialise_packet('O');
#if defined(USE_GPS)
ltm_serialise_32(GPS_home[LAT]);
ltm_serialise_32(GPS_home[LON]);
ltm_serialise_32(GPS_home[GPS_LATITUDE]);
ltm_serialise_32(GPS_home[GPS_LONGITUDE]);
#else
ltm_serialise_32(0);
ltm_serialise_32(0);

View file

@ -367,9 +367,9 @@ void mavlinkSendPosition(void)
mavlink_msg_gps_global_origin_pack(0, 200, &mavMsg,
// latitude Latitude (WGS84), expressed as * 1E7
GPS_home[LAT],
GPS_home[GPS_LATITUDE],
// longitude Longitude (WGS84), expressed as * 1E7
GPS_home[LON],
GPS_home[GPS_LONGITUDE],
// altitude Altitude(WGS84), expressed as * 1000
0);
msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavMsg);