AP_NavEKF3: Allow the GPS to be responsible for logging

This commit is contained in:
Michael du Breuil 2019-09-06 17:14:15 -07:00 committed by Andrew Tridgell
parent a4d10b2e86
commit 9a7d64e8fc
3 changed files with 0 additions and 7 deletions

View File

@ -610,10 +610,6 @@ void NavEKF3::check_log_write(void)
AP::logger().Write_Compass(imuSampleTime_us); AP::logger().Write_Compass(imuSampleTime_us);
logging.log_compass = false; 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) { if (logging.log_baro) {
AP::logger().Write_Baro(imuSampleTime_us); AP::logger().Write_Baro(imuSampleTime_us);
logging.log_baro = false; logging.log_baro = false;

View File

@ -486,7 +486,6 @@ private:
struct { struct {
bool enabled:1; bool enabled:1;
bool log_compass:1; bool log_compass:1;
bool log_gps:1;
bool log_baro:1; bool log_baro:1;
bool log_imu:1; bool log_imu:1;
} logging; } logging;

View File

@ -619,8 +619,6 @@ void NavEKF3_core::readGpsData()
gpsNotAvailable = false; gpsNotAvailable = false;
} }
frontend->logging.log_gps = true;
// if the GPS has yaw data then input that as well // if the GPS has yaw data then input that as well
float yaw_deg, yaw_accuracy_deg; float yaw_deg, yaw_accuracy_deg;
if (AP::gps().gps_yaw_deg(yaw_deg, yaw_accuracy_deg)) { if (AP::gps().gps_yaw_deg(yaw_deg, yaw_accuracy_deg)) {