Browse Source

AP_NavEKF3: Allow the GPS to be responsible for logging

mission-4.1.18
Michael du Breuil 5 years ago committed by Andrew Tridgell
parent
commit
9a7d64e8fc
  1. 4
      libraries/AP_NavEKF3/AP_NavEKF3.cpp
  2. 1
      libraries/AP_NavEKF3/AP_NavEKF3.h
  3. 2
      libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp

4
libraries/AP_NavEKF3/AP_NavEKF3.cpp

@ -610,10 +610,6 @@ void NavEKF3::check_log_write(void) @@ -610,10 +610,6 @@ void NavEKF3::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_NavEKF3/AP_NavEKF3.h

@ -486,7 +486,6 @@ private: @@ -486,7 +486,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_NavEKF3/AP_NavEKF3_Measurements.cpp

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

Loading…
Cancel
Save