Browse Source

AP_NavEKF2: log correct GPS for replay

master
priseborough 8 years ago committed by Randy Mackay
parent
commit
407a60e599
  1. 2
      libraries/AP_NavEKF2/AP_NavEKF2.cpp

2
libraries/AP_NavEKF2/AP_NavEKF2.cpp

@ -585,7 +585,7 @@ void NavEKF2::check_log_write(void) @@ -585,7 +585,7 @@ void NavEKF2::check_log_write(void)
logging.log_compass = false;
}
if (logging.log_gps) {
DataFlash_Class::instance()->Log_Write_GPS(_ahrs->get_gps(), 0, imuSampleTime_us);
DataFlash_Class::instance()->Log_Write_GPS(_ahrs->get_gps(), _ahrs->get_gps().primary_sensor(), imuSampleTime_us);
logging.log_gps = false;
}
if (logging.log_baro) {

Loading…
Cancel
Save