Browse Source

AP_Logger: moved log file open to logger thread

this prevents a watchdog if the filesystem takes a long time to
respond to a file open
c415-sdk
Andrew Tridgell 4 years ago
parent
commit
806fdd9389
  1. 17
      libraries/AP_Logger/AP_Logger_Backend.cpp
  2. 3
      libraries/AP_Logger/AP_Logger_Backend.h
  3. 47
      libraries/AP_Logger/AP_Logger_File.cpp
  4. 3
      libraries/AP_Logger/AP_Logger_File.h

17
libraries/AP_Logger/AP_Logger_Backend.cpp

@ -459,16 +459,25 @@ bool AP_Logger_Backend::ShouldLog(bool is_critical) @@ -459,16 +459,25 @@ bool AP_Logger_Backend::ShouldLog(bool is_critical)
return true;
}
void AP_Logger_Backend::PrepForArming()
// check if we should rotate when arming
void AP_Logger_Backend::arming_rotate_check(void)
{
if (_rotate_pending) {
_rotate_pending = false;
stop_logging();
}
if (logging_started()) {
return;
}
/*
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();
}
start_new_log();
}
bool AP_Logger_Backend::Write_MessageF(const char *fmt, ...)

3
libraries/AP_Logger/AP_Logger_Backend.h

@ -144,6 +144,9 @@ protected: @@ -144,6 +144,9 @@ protected:
virtual bool WritesOK() const = 0;
virtual bool StartNewLogOK() const;
// check if we should rotate when arming
void arming_rotate_check(void);
/*
read a block
*/

47
libraries/AP_Logger/AP_Logger_File.cpp

@ -435,17 +435,11 @@ bool AP_Logger_File::StartNewLogOK() const @@ -435,17 +435,11 @@ bool AP_Logger_File::StartNewLogOK() const
if (recent_open_error()) {
return false;
}
if (hal.scheduler->in_main_thread() &&
hal.util->get_soft_armed() &&
AP_HAL::millis() - hal.util->get_last_armed_change() > 3000) {
// when we create the log while arming we are armed and the
// creation is in the main loop. We generally don't want to
// allow logs to start in main thread while armed, but we
// have an exception for the first 3s after arming to allow
// for the normal arming process to work. This can be removed
// when we move log creation to the logging thread
#if !APM_BUILD_TYPE(APM_BUILD_Replay)
if (hal.scheduler->in_main_thread()) {
return false;
}
#endif
return AP_Logger_Backend::StartNewLogOK();
}
@ -715,6 +709,36 @@ void AP_Logger_File::stop_logging(void) @@ -715,6 +709,36 @@ void AP_Logger_File::stop_logging(void)
}
}
/*
wrapper for PrepForArming to move start_new_log to the logger thread
*/
void AP_Logger_File::PrepForArming()
{
#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;
/*
log open happens in the io_timer thread. We allow for a maximum
of 250ms to complete the open
*/
start_new_log_pending = true;
EXPECT_DELAY_MS(250);
while (AP_HAL::millis() - start_ms < open_limit_ms) {
if (logging_started()) {
break;
}
hal.scheduler->delay(1);
}
#endif
}
/*
start writing to a new log file
*/
@ -865,6 +889,11 @@ void AP_Logger_File::flush(void) @@ -865,6 +889,11 @@ void AP_Logger_File::flush(void)
void AP_Logger_File::io_timer(void)
{
if (start_new_log_pending) {
start_new_log();
start_new_log_pending = false;
}
uint32_t tnow = AP_HAL::millis();
_io_timer_heartbeat = tnow;

3
libraries/AP_Logger/AP_Logger_File.h

@ -61,6 +61,7 @@ protected: @@ -61,6 +61,7 @@ protected:
bool WritesOK() const override;
bool StartNewLogOK() const override;
void PrepForArming() override;
private:
int _write_fd = -1;
@ -134,6 +135,8 @@ private: @@ -134,6 +135,8 @@ private:
void erase_next(void);
const char *last_io_operation = "";
bool start_new_log_pending;
};
#endif // HAL_LOGGING_FILESYSTEM_ENABLED

Loading…
Cancel
Save