diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index c8f0af08c2..dffff235c4 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -596,10 +596,6 @@ void NavEKF2::check_log_write(void) AP::logger().Write_Compass(imuSampleTime_us); logging.log_compass = false; } - if (logging.log_gps) { - AP::logger().Write_GPS(AP::gps().primary_sensor(), imuSampleTime_us); - logging.log_gps = false; - } if (logging.log_baro) { AP::logger().Write_Baro(imuSampleTime_us); logging.log_baro = false; diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.h b/libraries/AP_NavEKF2/AP_NavEKF2.h index 8feaddafba..e5b4dee6ca 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2.h @@ -457,7 +457,6 @@ private: struct { bool enabled:1; bool log_compass:1; - bool log_gps:1; bool log_baro:1; bool log_imu:1; } logging; diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp index 76cbaf1441..fe05ad0ce5 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp @@ -600,8 +600,6 @@ void NavEKF2_core::readGpsData() gpsNotAvailable = false; } - frontend->logging.log_gps = true; - } else { // report GPS fix status gpsCheckStatus.bad_fix = true;