mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_Logger: on example sketches there is always time to write out FMT messages
This commit is contained in:
parent
f9451e36f5
commit
38bc9bfab1
@ -874,7 +874,7 @@ void AP_Logger_File::start_new_log(void)
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
void AP_Logger_File::flush(void)
|
||||
#if APM_BUILD_TYPE(APM_BUILD_Replay) || APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
|
||||
#if APM_BUILD_TYPE(APM_BUILD_Replay)
|
||||
{
|
||||
uint32_t tnow = AP_HAL::millis();
|
||||
while (_write_fd != -1 && _initialised && !recent_open_error() && _writebuf.available()) {
|
||||
|
@ -25,7 +25,7 @@ void LoggerMessageWriter::reset()
|
||||
|
||||
bool LoggerMessageWriter::out_of_time_for_writing_messages() const
|
||||
{
|
||||
#if HAL_SCHEDULER_ENABLED
|
||||
#if HAL_SCHEDULER_ENABLED && !APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
|
||||
return AP::scheduler().time_available_usec() < MIN_LOOP_TIME_REMAINING_FOR_MESSAGE_WRITE_US;
|
||||
#else
|
||||
return false;
|
||||
@ -62,7 +62,7 @@ bool LoggerMessageWriter_DFLogStart::out_of_time_for_writing_messages() const
|
||||
{
|
||||
if (stage == Stage::FORMATS) {
|
||||
// write out the FMT messages as fast as we can
|
||||
#if HAL_SCHEDULER_ENABLED
|
||||
#if HAL_SCHEDULER_ENABLED && !APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
|
||||
return AP::scheduler().time_available_usec() == 0;
|
||||
#else
|
||||
return false;
|
||||
|
Loading…
Reference in New Issue
Block a user