mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 12:55:19 +03:00
Merge pull request #6662 from awolf78/master
GPS over MSP related fixes
This commit is contained in:
commit
a8b92ea920
5 changed files with 26 additions and 6 deletions
|
@ -48,6 +48,7 @@
|
||||||
#include "io/beeper.h"
|
#include "io/beeper.h"
|
||||||
#include "io/ledstrip.h"
|
#include "io/ledstrip.h"
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
#include "io/gps.h"
|
||||||
|
|
||||||
#include "pg/beeper.h"
|
#include "pg/beeper.h"
|
||||||
#include "pg/beeper_dev.h"
|
#include "pg/beeper_dev.h"
|
||||||
|
@ -163,9 +164,15 @@ static void validateAndFixConfig(void)
|
||||||
pgResetFn_serialConfig(serialConfigMutable());
|
pgResetFn_serialConfig(serialConfigMutable());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if defined(USE_GPS)
|
||||||
|
serialPortConfig_t *gpsSerial = findSerialPortConfig(FUNCTION_GPS);
|
||||||
|
if (gpsConfig()->provider == GPS_MSP && gpsSerial) {
|
||||||
|
serialRemovePort(gpsSerial->identifier);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
if (
|
if (
|
||||||
#if defined(USE_GPS)
|
#if defined(USE_GPS)
|
||||||
!findSerialPortConfig(FUNCTION_GPS) &&
|
gpsConfig()->provider != GPS_MSP && !gpsSerial &&
|
||||||
#endif
|
#endif
|
||||||
true) {
|
true) {
|
||||||
featureDisable(FEATURE_GPS);
|
featureDisable(FEATURE_GPS);
|
||||||
|
@ -271,7 +278,7 @@ static void validateAndFixConfig(void)
|
||||||
pidProfilesMutable(i)->pid[PID_YAW].F = 0;
|
pidProfilesMutable(i)->pid[PID_YAW].F = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(USE_THROTTLE_BOOST)
|
#if defined(USE_THROTTLE_BOOST)
|
||||||
if (!rcSmoothingIsEnabled() ||
|
if (!rcSmoothingIsEnabled() ||
|
||||||
!(rxConfig()->rcInterpolationChannels == INTERPOLATION_CHANNELS_RPYT
|
!(rxConfig()->rcInterpolationChannels == INTERPOLATION_CHANNELS_RPYT
|
||||||
|
@ -409,7 +416,7 @@ void validateAndFixGyroConfig(void)
|
||||||
featureDisable(FEATURE_DYNAMIC_FILTER);
|
featureDisable(FEATURE_DYNAMIC_FILTER);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Prevent invalid notch cutoff
|
// Prevent invalid notch cutoff
|
||||||
if (gyroConfig()->gyro_soft_notch_cutoff_1 >= gyroConfig()->gyro_soft_notch_hz_1) {
|
if (gyroConfig()->gyro_soft_notch_cutoff_1 >= gyroConfig()->gyro_soft_notch_hz_1) {
|
||||||
gyroConfigMutable()->gyro_soft_notch_hz_1 = 0;
|
gyroConfigMutable()->gyro_soft_notch_hz_1 = 0;
|
||||||
|
|
|
@ -166,7 +166,7 @@ static const char * const lookupTableGyro[] = {
|
||||||
|
|
||||||
#ifdef USE_GPS
|
#ifdef USE_GPS
|
||||||
static const char * const lookupTableGPSProvider[] = {
|
static const char * const lookupTableGPSProvider[] = {
|
||||||
"NMEA", "UBLOX"
|
"NMEA", "UBLOX", "MSP"
|
||||||
};
|
};
|
||||||
|
|
||||||
static const char * const lookupTableGPSSBASMode[] = {
|
static const char * const lookupTableGPSSBASMode[] = {
|
||||||
|
|
|
@ -224,6 +224,7 @@ static const uint8_t ubloxGalileoInit[] = {
|
||||||
typedef enum {
|
typedef enum {
|
||||||
GPS_UNKNOWN,
|
GPS_UNKNOWN,
|
||||||
GPS_INITIALIZING,
|
GPS_INITIALIZING,
|
||||||
|
GPS_INITIALIZED,
|
||||||
GPS_CHANGE_BAUD,
|
GPS_CHANGE_BAUD,
|
||||||
GPS_CONFIGURE,
|
GPS_CONFIGURE,
|
||||||
GPS_RECEIVING_DATA,
|
GPS_RECEIVING_DATA,
|
||||||
|
@ -280,6 +281,11 @@ void gpsInit(void)
|
||||||
gpsSetState(GPS_UNKNOWN);
|
gpsSetState(GPS_UNKNOWN);
|
||||||
|
|
||||||
gpsData.lastMessage = millis();
|
gpsData.lastMessage = millis();
|
||||||
|
|
||||||
|
if (gpsConfig()->provider == GPS_MSP) { // no serial ports used when GPS_MSP is configured
|
||||||
|
gpsSetState(GPS_INITIALIZED);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
serialPortConfig_t *gpsPortConfig = findSerialPortConfig(FUNCTION_GPS);
|
serialPortConfig_t *gpsPortConfig = findSerialPortConfig(FUNCTION_GPS);
|
||||||
if (!gpsPortConfig) {
|
if (!gpsPortConfig) {
|
||||||
|
@ -474,6 +480,8 @@ void gpsInitHardware(void)
|
||||||
gpsInitUblox();
|
gpsInitUblox();
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -502,6 +510,7 @@ void gpsUpdate(timeUs_t currentTimeUs)
|
||||||
|
|
||||||
switch (gpsData.state) {
|
switch (gpsData.state) {
|
||||||
case GPS_UNKNOWN:
|
case GPS_UNKNOWN:
|
||||||
|
case GPS_INITIALIZED:
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case GPS_INITIALIZING:
|
case GPS_INITIALIZING:
|
||||||
|
@ -575,6 +584,8 @@ bool gpsNewFrame(uint8_t c)
|
||||||
return gpsNewFrameUBLOX(c);
|
return gpsNewFrameUBLOX(c);
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
|
@ -34,7 +34,8 @@
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
GPS_NMEA = 0,
|
GPS_NMEA = 0,
|
||||||
GPS_UBLOX
|
GPS_UBLOX,
|
||||||
|
GPS_MSP
|
||||||
} gpsProvider_e;
|
} gpsProvider_e;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
|
|
|
@ -449,11 +449,12 @@ void initCrsfTelemetry(void)
|
||||||
crsfSchedule[index++] = BV(CRSF_FRAME_BATTERY_SENSOR_INDEX);
|
crsfSchedule[index++] = BV(CRSF_FRAME_BATTERY_SENSOR_INDEX);
|
||||||
}
|
}
|
||||||
crsfSchedule[index++] = BV(CRSF_FRAME_FLIGHT_MODE_INDEX);
|
crsfSchedule[index++] = BV(CRSF_FRAME_FLIGHT_MODE_INDEX);
|
||||||
|
#ifdef USE_GPS
|
||||||
if (featureIsEnabled(FEATURE_GPS)) {
|
if (featureIsEnabled(FEATURE_GPS)) {
|
||||||
crsfSchedule[index++] = BV(CRSF_FRAME_GPS_INDEX);
|
crsfSchedule[index++] = BV(CRSF_FRAME_GPS_INDEX);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
crsfScheduleCount = (uint8_t)index;
|
crsfScheduleCount = (uint8_t)index;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool checkCrsfTelemetryState(void)
|
bool checkCrsfTelemetryState(void)
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue