mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: Add protection against bad GPS time delay values
Prevent bad values for GPS time delay pushing the GPS time stamp outside the range of IMU data contained in the buffer. If this occurs it can prevent the GPS measurements from being fused and cause loss of navigation.
This commit is contained in:
parent
e2757c17c8
commit
b723966b8d
|
@ -417,8 +417,8 @@ void NavEKF3_core::readGpsData()
|
|||
// Correct for the average intersampling delay due to the filter updaterate
|
||||
gpsDataNew.time_ms -= localFilterTimeStep_ms/2;
|
||||
|
||||
// Prevent time delay exceeding age of oldest IMU data in the buffer
|
||||
gpsDataNew.time_ms = MAX(gpsDataNew.time_ms,imuDataDelayed.time_ms);
|
||||
// Prevent the time stamp falling outside the oldest and newest IMU data in the buffer
|
||||
gpsDataNew.time_ms = MIN(MAX(gpsDataNew.time_ms,imuDataDelayed.time_ms),imuDataDownSampledNew.time_ms);
|
||||
|
||||
// Get which GPS we are using for position information
|
||||
gpsDataNew.sensor_idx = _ahrs->get_gps().primary_sensor();
|
||||
|
|
Loading…
Reference in New Issue