diff --git a/docs/Settings.md b/docs/Settings.md index cf9d031080..f909e698db 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -1414,7 +1414,7 @@ Yaw Iterm is frozen when bank angle is above this threshold [degrees]. This solv ### gps_auto_baud -Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS. When used with NAZA/DJI it will automatic detect GPS baudrate and change to it, ignoring the selected baudrate set in ports +Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS | Default | Min | Max | | --- | --- | --- | diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 1c968c8cf5..377e833a4b 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -506,7 +506,6 @@ main_sources(COMMON_SRC io/gps.h io/gps_ublox.c io/gps_nmea.c - io/gps_naza.c io/gps_msp.c io/gps_private.h io/ledstrip.c diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 0306b01788..9b03757c90 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -13,7 +13,7 @@ tables: values: ["NONE", "BNO055", "BNO055_SERIAL"] enum: secondaryImuType_e - name: mag_hardware - values: ["NONE", "AUTO", "HMC5883", "AK8975", "GPSMAG", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "MSP", "RM3100", "VCM5883", "MLX90393", "FAKE"] + values: ["NONE", "AUTO", "HMC5883", "AK8975", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "MSP", "RM3100", "VCM5883", "MLX90393", "FAKE"] enum: magSensor_e - name: opflow_hardware values: ["NONE", "CXOF", "MSP", "FAKE"] @@ -47,7 +47,7 @@ tables: values: ["NONE", "ADC", "ESC"] enum: voltageSensor_e - name: gps_provider - values: ["NMEA", "UBLOX", "NAZA", "UBLOX7", "MTK", "MSP"] + values: ["NMEA", "UBLOX", "UBLOX7", "MSP"] enum: gpsProvider_e - name: gps_sbas_mode values: ["AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "NONE"] @@ -1619,7 +1619,7 @@ groups: field: autoConfig type: bool - name: gps_auto_baud - description: "Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS. When used with NAZA/DJI it will automatic detect GPS baudrate and change to it, ignoring the selected baudrate set in ports" + description: "Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS" default_value: ON field: autoBaud type: bool diff --git a/src/main/io/gps.c b/src/main/io/gps.c index 6555bd2b2b..8483bc1ca7 100755 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -63,7 +63,6 @@ typedef struct { bool isDriverBased; portMode_t portMode; // Port mode RX/TX (only for serial based) - bool hasCompass; // Has a compass (NAZA) void (*restart)(void); // Restart protocol driver thread void (*protocol)(void); // Process protocol driver thread } gpsProviderDescriptor_t; @@ -79,41 +78,34 @@ baudRate_e gpsToSerialBaudRate[GPS_BAUDRATE_COUNT] = { BAUD_115200, BAUD_57600, static gpsProviderDescriptor_t gpsProviders[GPS_PROVIDER_COUNT] = { /* NMEA GPS */ #ifdef USE_GPS_PROTO_NMEA - { false, MODE_RX, false, &gpsRestartNMEA, &gpsHandleNMEA }, + { false, MODE_RX, gpsRestartNMEA, &gpsHandleNMEA }, #else - { false, 0, false, NULL, NULL }, + { false, 0, NULL, NULL }, #endif /* UBLOX binary */ #ifdef USE_GPS_PROTO_UBLOX - { false, MODE_RXTX, false, &gpsRestartUBLOX, &gpsHandleUBLOX }, + { false, MODE_RXTX, &gpsRestartUBLOX, &gpsHandleUBLOX }, #else - { false, 0, false, NULL, NULL }, -#endif - - /* NAZA GPS module */ -#ifdef USE_GPS_PROTO_NAZA - { false, MODE_RX, true, &gpsRestartNAZA, &gpsHandleNAZA }, -#else - { false, 0, false, NULL, NULL }, + { false, 0, NULL, NULL }, #endif /* UBLOX7PLUS binary */ #ifdef USE_GPS_PROTO_UBLOX - { false, MODE_RXTX, false, &gpsRestartUBLOX, &gpsHandleUBLOX }, + { false, MODE_RXTX, &gpsRestartUBLOX, &gpsHandleUBLOX }, #else - { false, 0, false, NULL, NULL }, + { false, 0, NULL, NULL }, #endif /* MSP GPS */ #ifdef USE_GPS_PROTO_MSP - { true, 0, false, &gpsRestartMSP, &gpsHandleMSP }, + { true, 0, &gpsRestartMSP, &gpsHandleMSP }, #else - { false, 0, false, NULL, NULL }, + { false, 0, NULL, NULL }, #endif }; -PG_REGISTER_WITH_RESET_TEMPLATE(gpsConfig_t, gpsConfig, PG_GPS_CONFIG, 1); +PG_REGISTER_WITH_RESET_TEMPLATE(gpsConfig_t, gpsConfig, PG_GPS_CONFIG, 2); PG_RESET_TEMPLATE(gpsConfig_t, gpsConfig, .provider = SETTING_GPS_PROVIDER_DEFAULT, @@ -440,36 +432,6 @@ void updateGpsIndicator(timeUs_t currentTimeUs) } } -/* Support for built-in magnetometer accessible via the native GPS protocol (i.e. NAZA) */ -bool gpsMagInit(magDev_t *magDev) -{ - UNUSED(magDev); - return true; -} - -bool gpsMagRead(magDev_t *magDev) -{ - magDev->magADCRaw[X] = gpsSol.magData[0]; - magDev->magADCRaw[Y] = gpsSol.magData[1]; - magDev->magADCRaw[Z] = gpsSol.magData[2]; - return gpsSol.flags.validMag; -} - -bool gpsMagDetect(magDev_t *mag) -{ - if (!(feature(FEATURE_GPS) && gpsProviders[gpsState.gpsConfig->provider].hasCompass)) { - return false; - } - - if (!gpsProviders[gpsState.gpsConfig->provider].protocol || !findSerialPortConfig(FUNCTION_GPS)) { - return false; - } - - mag->init = gpsMagInit; - mag->read = gpsMagRead; - return true; -} - bool isGPSHealthy(void) { return true; diff --git a/src/main/io/gps.h b/src/main/io/gps.h index a0f3e18a32..e887dae254 100755 --- a/src/main/io/gps.h +++ b/src/main/io/gps.h @@ -34,7 +34,6 @@ typedef enum { GPS_NMEA = 0, GPS_UBLOX, - GPS_NAZA, GPS_UBLOX7PLUS, GPS_MSP, GPS_PROVIDER_COUNT @@ -152,7 +151,6 @@ extern gpsSolutionData_t gpsSol; extern gpsStatistics_t gpsStats; struct magDev_s; -bool gpsMagDetect(struct magDev_s *mag); void gpsPreInit(void); void gpsInit(void); // Called periodically from GPS task. Returns true iff the GPS diff --git a/src/main/io/gps_naza.c b/src/main/io/gps_naza.c deleted file mode 100644 index 345dd2d2b2..0000000000 --- a/src/main/io/gps_naza.c +++ /dev/null @@ -1,383 +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 . - */ - -#include -#include -#include -#include -#include - -#include "platform.h" -#include "build/build_config.h" - - -#if defined(USE_GPS) && defined(USE_GPS_PROTO_NAZA) - -#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/gps.h" -#include "io/gps_private.h" -#include "io/serial.h" - -#include "scheduler/protothreads.h" - -#define NAZA_MAX_PAYLOAD_SIZE 256 - -typedef struct { - uint8_t res[4]; // 0 - uint8_t fw[4]; // 4 - uint8_t hw[4]; // 8 -} naza_ver; - -typedef struct { - uint16_t x; // 0 - uint16_t y; // 2 - uint16_t z; // 4 -} naza_mag; - -typedef struct { - uint32_t time; // GPS msToW 0 - int32_t longitude; // 4 - int32_t latitude; // 8 - int32_t altitude_msl; // 12 - int32_t h_acc; // 16 - int32_t v_acc; // 20 - int32_t reserved; - int32_t ned_north; // 28 - int32_t ned_east; // 32 - int32_t ned_down; // 36 - uint16_t pdop; // 40 - uint16_t vdop; // 42 - uint16_t ndop; // 44 - uint16_t edop; // 46 - uint8_t satellites; // 48 - uint8_t reserved3; // - uint8_t fix_type; // 50 - uint8_t reserved4; // - uint8_t fix_status; // 52 - uint8_t reserved5; - uint8_t reserved6; - uint8_t mask; // 55 -} naza_nav; - -enum { - HEADER1 = 0x55, - HEADER2 = 0xAA, - ID_NAV = 0x10, - ID_MAG = 0x20, - ID_VER = 0x30, - LEN_NAV = 0x3A, - LEN_MAG = 0x06, -} naza_protocol_bytes; - -typedef enum { - NO_FIX = 0, - FIX_2D = 2, - FIX_3D = 3, - FIX_DGPS = 4 -} fixType_t; - -// Receive buffer -static union { - naza_mag mag; - naza_nav nav; - naza_ver ver; - uint8_t bytes[NAZA_MAX_PAYLOAD_SIZE]; -} _buffernaza; - -// Packet checksum accumulators -static uint8_t _ck_a; -static uint8_t _ck_b; - -// State machine state -static bool _skip_packet; -static uint8_t _step; -static uint8_t _msg_id; -static uint16_t _payload_length; -static uint16_t _payload_counter; - -// do we have new position information? -static bool _new_position; - -// do we have new speed information? -static bool _new_speed; - -int32_t decodeLong(uint32_t idx, uint8_t mask) -{ - union { uint32_t l; uint8_t b[4]; } val; - val.l=idx; - for (int i = 0; i < 4; i++) val.b[i] ^= mask; - return val.l; -} - -int16_t decodeShort(uint16_t idx, uint8_t mask) -{ - union { uint16_t s; uint8_t b[2]; } val; - val.s=idx; - for (int i = 0; i < 2; i++) val.b[i] ^= mask; - return val.s; -} - -static bool NAZA_parse_gps(void) -{ - uint8_t mask; - uint8_t mask_mag; - - switch (_msg_id) { - case ID_NAV: - mask = _buffernaza.nav.mask; - - uint32_t time = decodeLong(_buffernaza.nav.time, mask); - gpsSol.time.seconds = time & 0b00111111; time >>= 6; - gpsSol.time.minutes = time & 0b00111111; time >>= 6; - gpsSol.time.hours = time & 0b00001111; time >>= 4; - gpsSol.time.day = gpsSol.time.hours > 7?(time & 0b00011111) + 1:(time & 0b00011111); time >>= 5; - gpsSol.time.month = time & 0b00001111; time >>= 4; - gpsSol.time.year = (time & 0b01111111) + 2000; - - gpsSol.llh.lon = decodeLong(_buffernaza.nav.longitude, mask); - gpsSol.llh.lat = decodeLong(_buffernaza.nav.latitude, mask); - gpsSol.llh.alt = decodeLong(_buffernaza.nav.altitude_msl, mask) / 10.0f; //alt in cm - - uint8_t fixType = _buffernaza.nav.fix_type ^ mask; - //uint8_t fixFlags = _buffernaza.nav.fix_status ^ mask; - - //uint8_t r3 = _buffernaza.nav.reserved3 ^ mask; - //uint8_t r4 = _buffernaza.nav.reserved4 ^ mask; - //uint8_t r5 = _buffernaza.nav.reserved5 ^ mask; - //uint8_t r6 = _buffernaza.nav.reserved6 ^ mask; - - if (fixType == FIX_2D) - gpsSol.fixType = GPS_FIX_2D; - else if (fixType == FIX_3D) - gpsSol.fixType = GPS_FIX_3D; - else - gpsSol.fixType = GPS_NO_FIX; - - uint32_t h_acc = decodeLong(_buffernaza.nav.h_acc, mask); // mm - uint32_t v_acc = decodeLong(_buffernaza.nav.v_acc, mask); // mm - //uint32_t test = decodeLong(_buffernaza.nav.reserved, mask); - - gpsSol.velNED[X] = decodeLong(_buffernaza.nav.ned_north, mask); // cm/s - gpsSol.velNED[Y] = decodeLong(_buffernaza.nav.ned_east, mask); // cm/s - gpsSol.velNED[Z] = decodeLong(_buffernaza.nav.ned_down, mask); // cm/s - - - uint16_t pdop = decodeShort(_buffernaza.nav.pdop, mask); // pdop - - gpsSol.hdop = gpsConstrainEPE(pdop); // PDOP - gpsSol.eph = gpsConstrainEPE(h_acc / 10); // hAcc in cm - gpsSol.epv = gpsConstrainEPE(v_acc / 10); // vAcc in cm - gpsSol.numSat = _buffernaza.nav.satellites; - gpsSol.groundSpeed = calc_length_pythagorean_2D(gpsSol.velNED[X], gpsSol.velNED[Y]); //cm/s - - // calculate gps heading from VELNE - gpsSol.groundCourse = (uint16_t)(fmodf(RADIANS_TO_DECIDEGREES(atan2_approx(gpsSol.velNED[Y], gpsSol.velNED[X])) + 3600.0f, 3600.0f)); - - gpsSol.flags.validVelNE = 1; - gpsSol.flags.validVelD = 1; - gpsSol.flags.validEPE = 1; - gpsSol.flags.validTime = 1; - - _new_position = true; - _new_speed = true; - break; - case ID_MAG: - mask_mag = (_buffernaza.mag.z)&0xFF; - mask_mag = (((mask_mag ^ (mask_mag >> 4)) & 0x0F) | ((mask_mag << 3) & 0xF0)) ^ (((mask_mag & 0x01) << 3) | ((mask_mag & 0x01) << 7)); - - gpsSol.magData[0] = decodeShort(_buffernaza.mag.x, mask_mag); - gpsSol.magData[1] = decodeShort(_buffernaza.mag.y, mask_mag); - gpsSol.magData[2] = (_buffernaza.mag.z ^ (mask_mag<<8)); - - gpsSol.flags.validMag = 1; - break; - case ID_VER: - break; - default: - return false; - } - - // we only return true when we get new position and speed data - // this ensures we don't use stale data - if (_new_position && _new_speed) { - _new_speed = _new_position = false; - return true; - } - return false; -} - -static bool gpsNewFrameNAZA(uint8_t data) -{ - bool parsed = false; - - switch (_step) { - case 0: // Sync char 1 (0x55) - if (HEADER1 == data) { - _skip_packet = false; - _step++; - } - break; - case 1: // Sync char 2 (0xAA) - if (HEADER2 != data) { - _step = 0; - break; - } - _step++; - break; - case 2: // Id - _step++; - _ck_b = _ck_a = data; // reset the checksum accumulators - _msg_id = data; - break; - case 3: // Payload length - _step++; - _ck_b += (_ck_a += data); // checksum byte - _payload_length = data; // payload length low byte - if (_payload_length > NAZA_MAX_PAYLOAD_SIZE) { - // we can't receive the whole packet, just log the error and start searching for the next packet. - gpsStats.errors++; - _step = 0; - break; - } - // prepare to receive payload - _payload_counter = 0; - if (_payload_length == 0) { - _step = 6; - } - break; - case 4: - _ck_b += (_ck_a += data); // checksum byte - if (_payload_counter < NAZA_MAX_PAYLOAD_SIZE) { - _buffernaza.bytes[_payload_counter] = data; - } - if (++_payload_counter >= _payload_length) { - _step++; - } - break; - case 5: - _step++; - if (_ck_a != data) { - _skip_packet = true; // bad checksum - gpsStats.errors++; - } - break; - case 6: - _step = 0; - if (_ck_b != data) { - gpsStats.errors++; - break; // bad checksum - } - - gpsStats.packetCount++; - - if (_skip_packet) { - break; - } - - if (NAZA_parse_gps()) { - parsed = true; - } - } - return parsed; -} - -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 (gpsNewFrameNAZA(newChar)) { - ptSemaphoreSignal(semNewDataReady); - break; - } - } - } - - ptEnd(0); -} - -STATIC_PROTOTHREAD(gpsProtocolStateThread) -{ - ptBegin(gpsProtocolStateThread); - - // 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 NAZA GPS - - // GPS setup done, reset timeout - gpsSetProtocolTimeout(GPS_TIMEOUT); - - // GPS is ready - execute the gpsProcessNewSolutionData() based on gpsProtocolReceiverThread semaphore - while (1) { - ptSemaphoreWait(semNewDataReady); - gpsProcessNewSolutionData(); - } - - ptEnd(0); -} - -void gpsRestartNAZA(void) -{ - ptSemaphoreInit(semNewDataReady); - ptRestart(ptGetHandle(gpsProtocolReceiverThread)); - ptRestart(ptGetHandle(gpsProtocolStateThread)); -} - -void gpsHandleNAZA(void) -{ - // Run the protocol threads - gpsProtocolReceiverThread(); - gpsProtocolStateThread(); - - // If thread stopped - signal communication loss and restart - if (ptIsStopped(ptGetHandle(gpsProtocolReceiverThread)) || ptIsStopped(ptGetHandle(gpsProtocolStateThread))) { - gpsSetState(GPS_LOST_COMMUNICATION); - } -} - -#endif diff --git a/src/main/io/gps_private.h b/src/main/io/gps_private.h index 59cae711e1..539689c62f 100755 --- a/src/main/io/gps_private.h +++ b/src/main/io/gps_private.h @@ -74,9 +74,6 @@ extern void gpsHandleUBLOX(void); extern void gpsRestartNMEA(void); extern void gpsHandleNMEA(void); -extern void gpsRestartNAZA(void); -extern void gpsHandleNAZA(void); - extern void gpsRestartMSP(void); extern void gpsHandleMSP(void); diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index 150d716c51..776483d33d 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -64,7 +64,7 @@ mag_t mag; // mag access functions #ifdef USE_MAG -PG_REGISTER_WITH_RESET_TEMPLATE(compassConfig_t, compassConfig, PG_COMPASS_CONFIG, 5); +PG_REGISTER_WITH_RESET_TEMPLATE(compassConfig_t, compassConfig, PG_COMPASS_CONFIG, 6); PG_RESET_TEMPLATE(compassConfig_t, compassConfig, .mag_align = SETTING_ALIGN_MAG_DEFAULT, @@ -146,19 +146,6 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse) } FALLTHROUGH; - case MAG_GPS: -#ifdef USE_GPS - if (gpsMagDetect(dev)) { - magHardware = MAG_GPS; - break; - } -#endif - /* If we are asked for a specific sensor - break out, otherwise - fall through and continue */ - if (magHardwareToUse != MAG_AUTODETECT) { - break; - } - FALLTHROUGH; - case MAG_MAG3110: #ifdef USE_MAG_MAG3110 if (mag3110detect(dev)) { diff --git a/src/main/sensors/compass.h b/src/main/sensors/compass.h index 9f798f28c5..27827649bb 100644 --- a/src/main/sensors/compass.h +++ b/src/main/sensors/compass.h @@ -29,22 +29,21 @@ // Type of magnetometer used/detected typedef enum { MAG_NONE = 0, - MAG_AUTODETECT = 1, - MAG_HMC5883 = 2, - MAG_AK8975 = 3, - MAG_GPS = 4, - MAG_MAG3110 = 5, - MAG_AK8963 = 6, - MAG_IST8310 = 7, - MAG_QMC5883 = 8, - MAG_MPU9250 = 9, - MAG_IST8308 = 10, - MAG_LIS3MDL = 11, - MAG_MSP = 12, - MAG_RM3100 = 13, - MAG_VCM5883 = 14, - MAG_MLX90393 = 15, - MAG_FAKE = 16, + MAG_AUTODETECT, + MAG_HMC5883, + MAG_AK8975, + MAG_MAG3110, + MAG_AK8963, + MAG_IST8310, + MAG_QMC5883, + MAG_MPU9250, + MAG_IST8308, + MAG_LIS3MDL, + MAG_MSP, + MAG_RM3100, + MAG_VCM5883, + MAG_MLX90393, + MAG_FAKE, MAG_MAX = MAG_FAKE } magSensor_e; diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h index f2e2289a2c..e6a01691e3 100644 --- a/src/main/target/MOTOLAB/target.h +++ b/src/main/target/MOTOLAB/target.h @@ -106,8 +106,6 @@ //#undef USE_GPS #undef USE_GPS_PROTO_NMEA //#undef USE_GPS_PROTO_UBLOX -#undef USE_GPS_PROTO_I2C_NAV -#undef USE_GPS_PROTO_NAZA // Number of available PWM outputs #define MAX_PWM_OUTPUT_PORTS 8 diff --git a/src/main/target/common.h b/src/main/target/common.h index 35f026cbe3..38767d2f20 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -94,9 +94,6 @@ #define USE_RATE_DYNAMICS #define USE_EXTENDED_CMS_MENUS -// NAZA GPS support for F4+ only -#define USE_GPS_PROTO_NAZA - // Allow default rangefinders #define USE_RANGEFINDER #define USE_RANGEFINDER_MSP diff --git a/src/test/unit/target.h b/src/test/unit/target.h index aa10b65180..4e50761db8 100755 --- a/src/test/unit/target.h +++ b/src/test/unit/target.h @@ -22,8 +22,6 @@ #define USE_GPS #define USE_GPS_PROTO_NMEA #define USE_GPS_PROTO_UBLOX -#define USE_GPS_PROTO_I2C_NAV -#define USE_GPS_PROTO_NAZA #define USE_DASHBOARD #define USE_TELEMETRY #define USE_TELEMETRY_FRSKY diff --git a/src/utils/rename-ifdefs.py b/src/utils/rename-ifdefs.py index d88259dd86..bf3f7826d2 100644 --- a/src/utils/rename-ifdefs.py +++ b/src/utils/rename-ifdefs.py @@ -28,8 +28,6 @@ RENAMES = [ 'TELEMETRY_FRSKY', 'CMS', 'GPS_PROTO_NMEA', - 'GPS_PROTO_I2C_NAV', - 'GPS_PROTO_NAZA', 'GPS_PROTO_UBLOX_NEO7PLUS', 'TELEMETRY_HOTT', 'TELEMETRY_IBUS',