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

GPS - handling incoming data as soon as possible to avoid observed GPS

packet loss.
This commit is contained in:
Dominic Clifton 2014-12-13 01:45:48 +00:00
parent 31ba3b7c94
commit 62134057f0
2 changed files with 10 additions and 15 deletions

View file

@ -19,11 +19,11 @@
// FIXME since serial ports can be used for any function these buffer sizes probably need normalising. // FIXME since serial ports can be used for any function these buffer sizes probably need normalising.
// Code is optimal when buffer sizes are powers of 2 due to use of % and / operators. // Code is optimal when buffer sizes are powers of 2 due to use of % and / operators.
#define UART1_RX_BUFFER_SIZE 192 #define UART1_RX_BUFFER_SIZE 256
#define UART1_TX_BUFFER_SIZE 192 #define UART1_TX_BUFFER_SIZE 192
#define UART2_RX_BUFFER_SIZE 192 #define UART2_RX_BUFFER_SIZE 256
#define UART2_TX_BUFFER_SIZE 192 #define UART2_TX_BUFFER_SIZE 192
#define UART3_RX_BUFFER_SIZE 192 #define UART3_RX_BUFFER_SIZE 256
#define UART3_TX_BUFFER_SIZE 192 #define UART3_TX_BUFFER_SIZE 192
typedef struct { typedef struct {

View file

@ -400,7 +400,6 @@ typedef enum {
#if defined(BARO) || defined(SONAR) #if defined(BARO) || defined(SONAR)
CALCULATE_ALTITUDE_TASK, CALCULATE_ALTITUDE_TASK,
#endif #endif
UPDATE_GPS_TASK,
UPDATE_DISPLAY_TASK UPDATE_DISPLAY_TASK
} periodicTasks; } periodicTasks;
@ -444,17 +443,6 @@ void executePeriodicTasks(void)
} }
break; break;
#endif #endif
#ifdef GPS
case UPDATE_GPS_TASK:
// if GPS feature is enabled, gpsThread() will be called at some intervals to check for stuck
// hardware, wrong baud rates, init GPS if needed, etc. Don't use SENSOR_GPS here as gpsThread() can and will
// change this based on available hardware
if (feature(FEATURE_GPS)) {
gpsThread();
}
break;
#endif
#ifdef SONAR #ifdef SONAR
case UPDATE_SONAR_TASK: case UPDATE_SONAR_TASK:
if (sensors(SENSOR_SONAR)) { if (sensors(SENSOR_SONAR)) {
@ -622,6 +610,13 @@ void loop(void)
} else { } else {
// not processing rx this iteration // not processing rx this iteration
executePeriodicTasks(); executePeriodicTasks();
// if GPS feature is enabled, gpsThread() will be called at some intervals to check for stuck
// hardware, wrong baud rates, init GPS if needed, etc. Don't use SENSOR_GPS here as gpsThread() can and will
// change this based on available hardware
if (feature(FEATURE_GPS)) {
gpsThread();
}
} }
currentTime = micros(); currentTime = micros();