Browse Source

AP_Logger: rearrange PrepForArming stuff

zr-v5.1
Peter Barker 4 years ago committed by Andrew Tridgell
parent
commit
151fe6facf
  1. 17
      libraries/AP_Logger/AP_Logger_Backend.cpp
  2. 6
      libraries/AP_Logger/AP_Logger_Backend.h
  3. 10
      libraries/AP_Logger/AP_Logger_File.cpp
  4. 2
      libraries/AP_Logger/AP_Logger_File.h

17
libraries/AP_Logger/AP_Logger_Backend.cpp

@ -459,25 +459,16 @@ bool AP_Logger_Backend::ShouldLog(bool is_critical) @@ -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, ...)

6
libraries/AP_Logger/AP_Logger_Backend.h

@ -144,8 +144,10 @@ protected: @@ -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

10
libraries/AP_Logger/AP_Logger_File.cpp

@ -710,17 +710,14 @@ void AP_Logger_File::stop_logging(void) @@ -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() @@ -736,7 +733,6 @@ void AP_Logger_File::PrepForArming()
}
hal.scheduler->delay(1);
}
#endif
}
/*

2
libraries/AP_Logger/AP_Logger_File.h

@ -61,7 +61,7 @@ protected: @@ -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;

Loading…
Cancel
Save