diff --git a/libraries/AP_Logger/AP_Logger_Backend.cpp b/libraries/AP_Logger/AP_Logger_Backend.cpp index 7258d7d068..382cea9d54 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.cpp +++ b/libraries/AP_Logger/AP_Logger_Backend.cpp @@ -459,25 +459,16 @@ bool AP_Logger_Backend::ShouldLog(bool is_critical) return true; } -// check if we should rotate when arming -void AP_Logger_Backend::arming_rotate_check(void) +void AP_Logger_Backend::PrepForArming() { if (_rotate_pending) { _rotate_pending = false; stop_logging(); } -} - -/* - setup for armed state, starting logging - This function is replaced in the File backend - */ -void AP_Logger_Backend::PrepForArming() -{ - arming_rotate_check(); - if (!logging_started()) { - start_new_log(); + if (logging_started()) { + return; } + PrepForArming_start_logging(); } bool AP_Logger_Backend::Write_MessageF(const char *fmt, ...) diff --git a/libraries/AP_Logger/AP_Logger_Backend.h b/libraries/AP_Logger/AP_Logger_Backend.h index 76ec09e65a..0a9ccc0707 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.h +++ b/libraries/AP_Logger/AP_Logger_Backend.h @@ -144,8 +144,10 @@ protected: virtual bool WritesOK() const = 0; virtual bool StartNewLogOK() const; - // check if we should rotate when arming - void arming_rotate_check(void); + // called by PrepForArming to actually start logging + virtual void PrepForArming_start_logging(void) { + start_new_log(); + } /* read a block diff --git a/libraries/AP_Logger/AP_Logger_File.cpp b/libraries/AP_Logger/AP_Logger_File.cpp index ac7ff4c014..8cc37686b3 100644 --- a/libraries/AP_Logger/AP_Logger_File.cpp +++ b/libraries/AP_Logger/AP_Logger_File.cpp @@ -710,17 +710,14 @@ void AP_Logger_File::stop_logging(void) } /* - wrapper for PrepForArming to move start_new_log to the logger thread + does start_new_log in the logger thread */ -void AP_Logger_File::PrepForArming() +void AP_Logger_File::PrepForArming_start_logging() { -#if APM_BUILD_TYPE(APM_BUILD_Replay) - AP_Logger_Backend::PrepForArming(); -#else - arming_rotate_check(); if (logging_started()) { return; } + uint32_t start_ms = AP_HAL::millis(); const uint32_t open_limit_ms = 250; @@ -736,7 +733,6 @@ void AP_Logger_File::PrepForArming() } hal.scheduler->delay(1); } -#endif } /* diff --git a/libraries/AP_Logger/AP_Logger_File.h b/libraries/AP_Logger/AP_Logger_File.h index 3a50c879db..499fe80ba0 100644 --- a/libraries/AP_Logger/AP_Logger_File.h +++ b/libraries/AP_Logger/AP_Logger_File.h @@ -61,7 +61,7 @@ protected: bool WritesOK() const override; bool StartNewLogOK() const override; - void PrepForArming() override; + void PrepForArming_start_logging() override; private: int _write_fd = -1;