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

Merge pull request #9302 from iNavFlight/dzikuvx-drop-nmea

Drop NMEA protocol
This commit is contained in:
Paweł Spychalski 2023-09-29 15:56:42 +02:00 committed by GitHub
commit bde9b929fe
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
11 changed files with 6 additions and 368 deletions

View file

@ -1864,7 +1864,7 @@ Weight of GPS altitude measurements in estimated altitude. Setting is used only
### inav_w_z_gps_v ### inav_w_z_gps_v
Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors.
| Default | Min | Max | | Default | Min | Max |
| --- | --- | --- | | --- | --- | --- |

View file

@ -506,7 +506,6 @@ main_sources(COMMON_SRC
io/gps.h io/gps.h
io/gps_ublox.c io/gps_ublox.c
io/gps_ublox_utils.c io/gps_ublox_utils.c
io/gps_nmea.c
io/gps_msp.c io/gps_msp.c
io/gps_fake.c io/gps_fake.c
io/gps_private.h io/gps_private.h

View file

@ -44,7 +44,7 @@ tables:
values: ["VELNED", "TURNRATE","ADAPTIVE"] values: ["VELNED", "TURNRATE","ADAPTIVE"]
enum: imu_inertia_comp_method_e enum: imu_inertia_comp_method_e
- name: gps_provider - name: gps_provider
values: ["NMEA", "UBLOX", "UBLOX7", "MSP", "FAKE"] values: ["UBLOX", "UBLOX7", "MSP", "FAKE"]
enum: gpsProvider_e enum: gpsProvider_e
- name: gps_sbas_mode - name: gps_sbas_mode
values: ["AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "SPAN", "NONE"] values: ["AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "SPAN", "NONE"]
@ -2267,7 +2267,7 @@ groups:
max: 10 max: 10
default_value: 0.2 default_value: 0.2
- name: inav_w_z_gps_v - name: inav_w_z_gps_v
description: "Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero" description: "Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors."
field: w_z_gps_v field: w_z_gps_v
min: 0 min: 0
max: 10 max: 10

View file

@ -77,13 +77,6 @@ gpsSolutionData_t gpsSol;
baudRate_e gpsToSerialBaudRate[GPS_BAUDRATE_COUNT] = { BAUD_115200, BAUD_57600, BAUD_38400, BAUD_19200, BAUD_9600, BAUD_230400, BAUD_460800, BAUD_921600 }; baudRate_e gpsToSerialBaudRate[GPS_BAUDRATE_COUNT] = { BAUD_115200, BAUD_57600, BAUD_38400, BAUD_19200, BAUD_9600, BAUD_230400, BAUD_460800, BAUD_921600 };
static gpsProviderDescriptor_t gpsProviders[GPS_PROVIDER_COUNT] = { static gpsProviderDescriptor_t gpsProviders[GPS_PROVIDER_COUNT] = {
/* NMEA GPS */
#ifdef USE_GPS_PROTO_NMEA
{ false, MODE_RX, gpsRestartNMEA, &gpsHandleNMEA },
#else
{ false, 0, NULL, NULL },
#endif
/* UBLOX binary */ /* UBLOX binary */
#ifdef USE_GPS_PROTO_UBLOX #ifdef USE_GPS_PROTO_UBLOX
{ false, MODE_RXTX, &gpsRestartUBLOX, &gpsHandleUBLOX }, { false, MODE_RXTX, &gpsRestartUBLOX, &gpsHandleUBLOX },
@ -113,7 +106,7 @@ static gpsProviderDescriptor_t gpsProviders[GPS_PROVIDER_COUNT] = {
}; };
PG_REGISTER_WITH_RESET_TEMPLATE(gpsConfig_t, gpsConfig, PG_GPS_CONFIG, 4); PG_REGISTER_WITH_RESET_TEMPLATE(gpsConfig_t, gpsConfig, PG_GPS_CONFIG, 5);
PG_RESET_TEMPLATE(gpsConfig_t, gpsConfig, PG_RESET_TEMPLATE(gpsConfig_t, gpsConfig,
.provider = SETTING_GPS_PROVIDER_DEFAULT, .provider = SETTING_GPS_PROVIDER_DEFAULT,
@ -264,7 +257,7 @@ void gpsPreInit(void)
{ {
// Make sure gpsProvider is known when gpsMagDetect is called // Make sure gpsProvider is known when gpsMagDetect is called
gpsState.gpsConfig = gpsConfig(); gpsState.gpsConfig = gpsConfig();
gpsState.baseTimeoutMs = (gpsState.gpsConfig->provider == GPS_NMEA) ? GPS_TIMEOUT*2 : GPS_TIMEOUT; gpsState.baseTimeoutMs = GPS_TIMEOUT;
} }
void gpsInit(void) void gpsInit(void)

View file

@ -33,8 +33,7 @@
#define GPS_DEGREES_DIVIDER 10000000L #define GPS_DEGREES_DIVIDER 10000000L
typedef enum { typedef enum {
GPS_NMEA = 0, GPS_UBLOX = 0,
GPS_UBLOX,
GPS_UBLOX7PLUS, GPS_UBLOX7PLUS,
GPS_MSP, GPS_MSP,
GPS_FAKE, GPS_FAKE,

View file

@ -1,340 +0,0 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <ctype.h>
#include <string.h>
#include <math.h>
#include "platform.h"
#if defined(USE_GPS) && (defined(USE_GPS_PROTO_NMEA))
#include "build/build_config.h"
#include "build/debug.h"
#include "common/axis.h"
#include "common/gps_conversion.h"
#include "common/maths.h"
#include "common/utils.h"
#include "drivers/serial.h"
#include "drivers/time.h"
#include "fc/config.h"
#include "fc/runtime_config.h"
#include "io/serial.h"
#include "io/gps.h"
#include "io/gps_private.h"
#include "scheduler/protothreads.h"
/* This is a light implementation of a GPS frame decoding
This should work with most of modern GPS devices configured to output 5 frames.
It assumes there are some NMEA GGA frames to decode on the serial bus
Now verifies checksum correctly before applying data
Here we use only the following data :
- latitude
- longitude
- GPS fix is/is not ok
- GPS num sat (4 is enough to be +/- reliable)
// added by Mis
- GPS altitude (for OSD displaying)
- GPS speed (for OSD displaying)
*/
#define NO_FRAME 0
#define FRAME_GGA 1
#define FRAME_RMC 2
static uint32_t grab_fields(char *src, uint8_t mult)
{ // convert string to uint32
uint32_t i;
uint32_t tmp = 0;
for (i = 0; src[i] != 0; i++) {
if (src[i] == '.') {
i++;
if (mult == 0)
break;
else
src[i + mult] = 0;
}
tmp *= 10;
if (src[i] >= '0' && src[i] <= '9')
tmp += src[i] - '0';
if (i >= 15)
return 0; // out of bounds
}
return tmp;
}
typedef struct gpsDataNmea_s {
bool fix;
int32_t latitude;
int32_t longitude;
uint8_t numSat;
int32_t altitude;
uint16_t speed;
uint16_t ground_course;
uint16_t hdop;
uint32_t time;
uint32_t date;
} gpsDataNmea_t;
#define NMEA_BUFFER_SIZE 16
static bool gpsNewFrameNMEA(char c)
{
static gpsDataNmea_t gps_Msg;
uint8_t frameOK = 0;
static uint8_t param = 0, offset = 0, parity = 0;
static char string[NMEA_BUFFER_SIZE];
static uint8_t checksum_param, gps_frame = NO_FRAME;
switch (c) {
case '$':
param = 0;
offset = 0;
parity = 0;
break;
case ',':
case '*':
string[offset] = 0;
if (param == 0) { //frame identification
gps_frame = NO_FRAME;
if (strcmp(string, "GPGGA") == 0 || strcmp(string, "GNGGA") == 0) {
gps_frame = FRAME_GGA;
}
else if (strcmp(string, "GPRMC") == 0 || strcmp(string, "GNRMC") == 0) {
gps_frame = FRAME_RMC;
}
}
switch (gps_frame) {
case FRAME_GGA: //************* GPGGA FRAME parsing
switch (param) {
// case 1: // Time information
// break;
case 2:
gps_Msg.latitude = GPS_coord_to_degrees(string);
break;
case 3:
if (string[0] == 'S')
gps_Msg.latitude *= -1;
break;
case 4:
gps_Msg.longitude = GPS_coord_to_degrees(string);
break;
case 5:
if (string[0] == 'W')
gps_Msg.longitude *= -1;
break;
case 6:
if (string[0] > '0') {
gps_Msg.fix = true;
} else {
gps_Msg.fix = false;
}
break;
case 7:
gps_Msg.numSat = grab_fields(string, 0);
break;
case 8:
gps_Msg.hdop = grab_fields(string, 1) * 10; // hdop
break;
case 9:
gps_Msg.altitude = grab_fields(string, 1) * 10; // altitude in cm
break;
}
break;
case FRAME_RMC: //************* GPRMC FRAME parsing
// $GNRMC,130059.00,V,,,,,,,110917,,,N*62
switch (param) {
case 1:
gps_Msg.time = grab_fields(string, 2);
break;
case 7:
gps_Msg.speed = ((grab_fields(string, 1) * 5144L) / 1000L); // speed in cm/s added by Mis
break;
case 8:
gps_Msg.ground_course = (grab_fields(string, 1)); // ground course deg * 10
break;
case 9:
gps_Msg.date = grab_fields(string, 0);
break;
}
break;
}
param++;
offset = 0;
if (c == '*')
checksum_param = 1;
else
parity ^= c;
break;
case '\r':
case '\n':
if (checksum_param) { //parity checksum
uint8_t checksum = 16 * ((string[0] >= 'A') ? string[0] - 'A' + 10 : string[0] - '0') + ((string[1] >= 'A') ? string[1] - 'A' + 10 : string[1] - '0');
if (checksum == parity) {
gpsStats.packetCount++;
switch (gps_frame) {
case FRAME_GGA:
frameOK = 1;
gpsSol.numSat = gps_Msg.numSat;
if (gps_Msg.fix) {
gpsSol.fixType = GPS_FIX_3D; // NMEA doesn't report fix type, assume 3D
gpsSol.llh.lat = gps_Msg.latitude;
gpsSol.llh.lon = gps_Msg.longitude;
gpsSol.llh.alt = gps_Msg.altitude;
// EPH/EPV are unreliable for NMEA as they are not real accuracy
gpsSol.hdop = gpsConstrainHDOP(gps_Msg.hdop);
gpsSol.eph = gpsConstrainEPE(gps_Msg.hdop * GPS_HDOP_TO_EPH_MULTIPLIER);
gpsSol.epv = gpsConstrainEPE(gps_Msg.hdop * GPS_HDOP_TO_EPH_MULTIPLIER);
gpsSol.flags.validEPE = false;
}
else {
gpsSol.fixType = GPS_NO_FIX;
}
// NMEA does not report VELNED
gpsSol.flags.validVelNE = false;
gpsSol.flags.validVelD = false;
break;
case FRAME_RMC:
gpsSol.groundSpeed = gps_Msg.speed;
gpsSol.groundCourse = gps_Msg.ground_course;
// This check will miss 00:00:00.00, but we shouldn't care - next report will be valid
if (gps_Msg.date != 0 && gps_Msg.time != 0) {
gpsSol.time.year = (gps_Msg.date % 100) + 2000;
gpsSol.time.month = (gps_Msg.date / 100) % 100;
gpsSol.time.day = (gps_Msg.date / 10000) % 100;
gpsSol.time.hours = (gps_Msg.time / 1000000) % 100;
gpsSol.time.minutes = (gps_Msg.time / 10000) % 100;
gpsSol.time.seconds = (gps_Msg.time / 100) % 100;
gpsSol.time.millis = (gps_Msg.time & 100) * 10;
gpsSol.flags.validTime = true;
}
else {
gpsSol.flags.validTime = false;
}
break;
} // end switch
}
else {
gpsStats.errors++;
}
}
checksum_param = 0;
break;
default:
if (offset < (NMEA_BUFFER_SIZE-1)) { // leave 1 byte to trailing zero
string[offset++] = c;
// only checksum if character is recorded and used (will cause checksum failure on dropped characters)
if (!checksum_param)
parity ^= c;
}
}
return frameOK;
}
static ptSemaphore_t semNewDataReady;
STATIC_PROTOTHREAD(gpsProtocolReceiverThread)
{
ptBegin(gpsProtocolReceiverThread);
while (1) {
// Wait until there are bytes to consume
ptWait(serialRxBytesWaiting(gpsState.gpsPort));
// Consume bytes until buffer empty of until we have full message received
while (serialRxBytesWaiting(gpsState.gpsPort)) {
uint8_t newChar = serialRead(gpsState.gpsPort);
if (gpsNewFrameNMEA(newChar)) {
gpsSol.flags.validVelNE = false;
gpsSol.flags.validVelD = false;
ptSemaphoreSignal(semNewDataReady);
break;
}
}
}
ptEnd(0);
}
STATIC_PROTOTHREAD(gpsProtocolStateThreadNMEA)
{
ptBegin(gpsProtocolStateThreadNMEA);
// Change baud rate
ptWait(isSerialTransmitBufferEmpty(gpsState.gpsPort));
if (gpsState.gpsConfig->autoBaud != GPS_AUTOBAUD_OFF) {
// Cycle through available baud rates and hope that we will match GPS
serialSetBaudRate(gpsState.gpsPort, baudRates[gpsToSerialBaudRate[gpsState.autoBaudrateIndex]]);
gpsState.autoBaudrateIndex = (gpsState.autoBaudrateIndex + 1) % GPS_BAUDRATE_COUNT;
ptDelayMs(GPS_BAUD_CHANGE_DELAY);
}
else {
// Set baud rate
serialSetBaudRate(gpsState.gpsPort, baudRates[gpsToSerialBaudRate[gpsState.baudrateIndex]]);
}
// No configuration is done for pure NMEA modules
// GPS setup done, reset timeout
gpsSetProtocolTimeout(gpsState.baseTimeoutMs);
// GPS is ready - execute the gpsProcessNewSolutionData() based on gpsProtocolReceiverThread semaphore
while (1) {
ptSemaphoreWait(semNewDataReady);
gpsProcessNewSolutionData();
}
ptEnd(0);
}
void gpsHandleNMEA(void)
{
// Run the protocol threads
gpsProtocolReceiverThread();
gpsProtocolStateThreadNMEA();
// If thread stopped - signal communication loss and restart
if (ptIsStopped(ptGetHandle(gpsProtocolReceiverThread)) || ptIsStopped(ptGetHandle(gpsProtocolStateThreadNMEA))) {
gpsSetState(GPS_LOST_COMMUNICATION);
}
}
void gpsRestartNMEA(void)
{
ptSemaphoreInit(semNewDataReady);
ptRestart(ptGetHandle(gpsProtocolReceiverThread));
ptRestart(ptGetHandle(gpsProtocolStateThreadNMEA));
}
#endif

View file

@ -76,9 +76,6 @@ void gpsSetProtocolTimeout(timeMs_t timeoutMs);
extern void gpsRestartUBLOX(void); extern void gpsRestartUBLOX(void);
extern void gpsHandleUBLOX(void); extern void gpsHandleUBLOX(void);
extern void gpsRestartNMEA(void);
extern void gpsHandleNMEA(void);
extern void gpsRestartMSP(void); extern void gpsRestartMSP(void);
extern void gpsHandleMSP(void); extern void gpsHandleMSP(void);

View file

@ -121,8 +121,6 @@
#define USE_I2C_IO_EXPANDER #define USE_I2C_IO_EXPANDER
#define USE_GPS_PROTO_NMEA
#define USE_TELEMETRY_SIM #define USE_TELEMETRY_SIM
#define USE_TELEMETRY_MAVLINK #define USE_TELEMETRY_MAVLINK
#define USE_MSP_OVER_TELEMETRY #define USE_MSP_OVER_TELEMETRY

View file

@ -30,12 +30,6 @@
#include "io/serial.h" #include "io/serial.h"
typedef enum {
FRSKY_FORMAT_DMS = 0,
FRSKY_FORMAT_NMEA
} frskyGpsCoordFormat_e;
typedef enum { typedef enum {
LTM_RATE_NORMAL, LTM_RATE_NORMAL,
LTM_RATE_MEDIUM, LTM_RATE_MEDIUM,

View file

@ -21,7 +21,6 @@
#define USE_MAG #define USE_MAG
#define USE_BARO #define USE_BARO
#define USE_GPS #define USE_GPS
#define USE_GPS_PROTO_NMEA
#define USE_GPS_PROTO_UBLOX #define USE_GPS_PROTO_UBLOX
#define USE_DASHBOARD #define USE_DASHBOARD
#define USE_TELEMETRY #define USE_TELEMETRY

View file

@ -27,7 +27,6 @@ RENAMES = [
'TELEMETRY_LTM', 'TELEMETRY_LTM',
'TELEMETRY_FRSKY', 'TELEMETRY_FRSKY',
'CMS', 'CMS',
'GPS_PROTO_NMEA',
'GPS_PROTO_UBLOX_NEO7PLUS', 'GPS_PROTO_UBLOX_NEO7PLUS',
'TELEMETRY_HOTT', 'TELEMETRY_HOTT',
'TELEMETRY_IBUS', 'TELEMETRY_IBUS',