mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-31 04:58:30 -04:00
prevent duplicate EKF logging
vehicle code sometimes tries to log the same data twice
This commit is contained in:
parent
fa75824948
commit
f3c3778169
@ -477,6 +477,9 @@ private:
|
|||||||
// time at start of current filter update
|
// time at start of current filter update
|
||||||
uint64_t imuSampleTime_us;
|
uint64_t imuSampleTime_us;
|
||||||
|
|
||||||
|
// last time of Log_Write
|
||||||
|
uint64_t lastLogWrite_us;
|
||||||
|
|
||||||
struct {
|
struct {
|
||||||
uint32_t last_function_call; // last time getLastYawResetAngle was called
|
uint32_t last_function_call; // last time getLastYawResetAngle was called
|
||||||
bool core_changed; // true when a core change happened and hasn't been consumed, false otherwise
|
bool core_changed; // true when a core change happened and hasn't been consumed, false otherwise
|
||||||
|
@ -288,6 +288,12 @@ void NavEKF2::Log_Write()
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (lastLogWrite_us == imuSampleTime_us) {
|
||||||
|
// vehicle is doubling up on logging
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
lastLogWrite_us = imuSampleTime_us;
|
||||||
|
|
||||||
const uint64_t time_us = AP::dal().micros64();
|
const uint64_t time_us = AP::dal().micros64();
|
||||||
|
|
||||||
// note that several of these functions exit-early if they're not
|
// note that several of these functions exit-early if they're not
|
||||||
|
@ -534,6 +534,9 @@ private:
|
|||||||
// time of last lane switch
|
// time of last lane switch
|
||||||
uint32_t lastLaneSwitch_ms;
|
uint32_t lastLaneSwitch_ms;
|
||||||
|
|
||||||
|
// last time of Log_Write
|
||||||
|
uint64_t lastLogWrite_us;
|
||||||
|
|
||||||
struct {
|
struct {
|
||||||
uint32_t last_function_call; // last time getLastYawResetAngle was called
|
uint32_t last_function_call; // last time getLastYawResetAngle was called
|
||||||
bool core_changed; // true when a core change happened and hasn't been consumed, false otherwise
|
bool core_changed; // true when a core change happened and hasn't been consumed, false otherwise
|
||||||
|
@ -352,6 +352,11 @@ void NavEKF3::Log_Write()
|
|||||||
if (activeCores() <= 0) {
|
if (activeCores() <= 0) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
if (lastLogWrite_us == imuSampleTime_us) {
|
||||||
|
// vehicle is doubling up on logging
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
lastLogWrite_us = imuSampleTime_us;
|
||||||
|
|
||||||
uint64_t time_us = AP::dal().micros64();
|
uint64_t time_us = AP::dal().micros64();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user