mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
added check for duplicate time-stamped GPS messages.
This commit is contained in:
parent
07dac1a5a7
commit
f8ceec2b4b
@ -869,7 +869,8 @@ static int16_t superslow_loopCounter;
|
||||
static uint32_t loiter_timer;
|
||||
// disarms the copter while in Acro or Stabilize mode after 30 seconds of no flight
|
||||
static uint8_t auto_disarming_counter;
|
||||
|
||||
// prevents duplicate GPS messages from entering system
|
||||
static uint32_t last_gps_time;
|
||||
|
||||
// Tracks if GPS is enabled based on statup routine
|
||||
// If we do not detect GPS at startup, we stop trying and assume GPS is not connected
|
||||
@ -1351,17 +1352,22 @@ static void update_GPS(void)
|
||||
}
|
||||
|
||||
if (g_gps->new_data && g_gps->fix) {
|
||||
|
||||
// clear new data flag
|
||||
g_gps->new_data = false;
|
||||
|
||||
// check for duiplicate GPS messages
|
||||
if(last_gps_time != g_gps->time){
|
||||
|
||||
// look for broken GPS
|
||||
// ---------------
|
||||
gps_watchdog = 0;
|
||||
|
||||
// OK to run the nav routines
|
||||
// ---------------
|
||||
nav_ok = true;
|
||||
|
||||
// for performance
|
||||
// ---------------
|
||||
// for performance monitoring
|
||||
// --------------------------
|
||||
gps_fix_count++;
|
||||
|
||||
// used to calculate speed in X and Y, iterms
|
||||
@ -1409,6 +1415,10 @@ static void update_GPS(void)
|
||||
alt_sensor_flag = true;
|
||||
#endif
|
||||
}
|
||||
|
||||
// save GPS time so we don't get duplicate reads
|
||||
last_gps_time = g_gps->time;
|
||||
}
|
||||
}
|
||||
|
||||
void update_yaw_mode(void)
|
||||
|
Loading…
Reference in New Issue
Block a user