Browse Source

AP_NavEKF2: Allow the GPS to be responsible for logging

master
Michael du Breuil 6 years ago committed by Andrew Tridgell
parent
commit
a4d10b2e86
  1. 4
      libraries/AP_NavEKF2/AP_NavEKF2.cpp
  2. 1
      libraries/AP_NavEKF2/AP_NavEKF2.h
  3. 2
      libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp

4
libraries/AP_NavEKF2/AP_NavEKF2.cpp

@ -596,10 +596,6 @@ void NavEKF2::check_log_write(void) @@ -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;

1
libraries/AP_NavEKF2/AP_NavEKF2.h

@ -457,7 +457,6 @@ private: @@ -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;

2
libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp

@ -600,8 +600,6 @@ void NavEKF2_core::readGpsData() @@ -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…
Cancel
Save