mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: fixed gaps in EKF logging
timestamps should not be static as otherwise some lanes will not be logged
This commit is contained in:
parent
281f041abb
commit
52209d9d1a
|
@ -252,7 +252,6 @@ void NavEKF2_core::Log_Write_Beacon(uint64_t time_us)
|
|||
void NavEKF2_core::Log_Write_Timing(uint64_t time_us)
|
||||
{
|
||||
// log EKF timing statistics every 5s
|
||||
static uint32_t lastTimingLogTime_ms = 0;
|
||||
if (AP::dal().millis() - lastTimingLogTime_ms <= 5000) {
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -1178,6 +1178,9 @@ private:
|
|||
uint8_t EKFGSF_yaw_reset_count; // number of emergency yaw resets performed
|
||||
bool EKFGSF_run_filterbank; // true when the filter bank is active
|
||||
|
||||
// logging timestamps
|
||||
uint32_t lastTimingLogTime_ms;
|
||||
|
||||
// logging functions shared by cores:
|
||||
void Log_Write_NKF1(uint64_t time_us) const;
|
||||
void Log_Write_NKF2(uint64_t time_us) const;
|
||||
|
|
Loading…
Reference in New Issue