Skip to content

Commit

Permalink
AP_NavEKF3: Allow the GPS to be responsible for logging
Browse files Browse the repository at this point in the history
  • Loading branch information
WickedShell authored and tridge committed Sep 9, 2019
1 parent a4d10b2 commit 9a7d64e
Show file tree
Hide file tree
Showing 3 changed files with 0 additions and 7 deletions.
4 changes: 0 additions & 4 deletions libraries/AP_NavEKF3/AP_NavEKF3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
1 change: 0 additions & 1 deletion libraries/AP_NavEKF3/AP_NavEKF3.h
Original file line number Diff line number Diff line change
Expand Up @@ -486,7 +486,6 @@ class NavEKF3 {
struct {
bool enabled:1;
bool log_compass:1;
bool log_gps:1;
bool log_baro:1;
bool log_imu:1;
} logging;
Expand Down
2 changes: 0 additions & 2 deletions libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)) {
Expand Down

0 comments on commit 9a7d64e

Please sign in to comment.