mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: Allow the GPS to be responsible for logging
This commit is contained in:
parent
f857eb4640
commit
a4d10b2e86
|
@ -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;
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -600,8 +600,6 @@ void NavEKF2_core::readGpsData()
|
|||
gpsNotAvailable = false;
|
||||
}
|
||||
|
||||
frontend->logging.log_gps = true;
|
||||
|
||||
} else {
|
||||
// report GPS fix status
|
||||
gpsCheckStatus.bad_fix = true;
|
||||
|
|
Loading…
Reference in New Issue