mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-02 11:43:56 -04:00
DataFlash: resolve race conditions with IMU logging thread
This commit is contained in:
parent
17ef7e68b1
commit
f9f20970c9
@ -86,6 +86,12 @@ bool DataFlash_Backend::WriteBlockCheckStartupMessages()
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (!_startup_messagewriter->finished() &&
|
||||||
|
!hal.scheduler->in_main_thread()) {
|
||||||
|
// only the main thread may write startup messages out
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
// we're not writing startup messages, so this must be some random
|
// we're not writing startup messages, so this must be some random
|
||||||
// caller hoping to write blocks out. Push out log blocks - we
|
// caller hoping to write blocks out. Push out log blocks - we
|
||||||
// might end up clearing the buffer.....
|
// might end up clearing the buffer.....
|
||||||
@ -271,6 +277,9 @@ bool DataFlash_Backend::StartNewLogOK() const
|
|||||||
if (_front.in_log_download()) {
|
if (_front.in_log_download()) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
if (!hal.scheduler->in_main_thread()) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -300,5 +309,11 @@ bool DataFlash_Backend::ShouldLog() const
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (!_startup_messagewriter->finished() &&
|
||||||
|
!hal.scheduler->in_main_thread()) {
|
||||||
|
// only the main thread may write startup messages out
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user