mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
AP_Logger: rearrange PrepForArming stuff
This commit is contained in:
parent
a1f8d4c79c
commit
357770deba
@ -459,25 +459,16 @@ bool AP_Logger_Backend::ShouldLog(bool is_critical)
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// check if we should rotate when arming
|
void AP_Logger_Backend::PrepForArming()
|
||||||
void AP_Logger_Backend::arming_rotate_check(void)
|
|
||||||
{
|
{
|
||||||
if (_rotate_pending) {
|
if (_rotate_pending) {
|
||||||
_rotate_pending = false;
|
_rotate_pending = false;
|
||||||
stop_logging();
|
stop_logging();
|
||||||
}
|
}
|
||||||
|
if (logging_started()) {
|
||||||
|
return;
|
||||||
}
|
}
|
||||||
|
PrepForArming_start_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();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_Logger_Backend::Write_MessageF(const char *fmt, ...)
|
bool AP_Logger_Backend::Write_MessageF(const char *fmt, ...)
|
||||||
|
@ -144,8 +144,10 @@ protected:
|
|||||||
virtual bool WritesOK() const = 0;
|
virtual bool WritesOK() const = 0;
|
||||||
virtual bool StartNewLogOK() const;
|
virtual bool StartNewLogOK() const;
|
||||||
|
|
||||||
// check if we should rotate when arming
|
// called by PrepForArming to actually start logging
|
||||||
void arming_rotate_check(void);
|
virtual void PrepForArming_start_logging(void) {
|
||||||
|
start_new_log();
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
read a block
|
read a block
|
||||||
|
@ -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()) {
|
if (logging_started()) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t start_ms = AP_HAL::millis();
|
uint32_t start_ms = AP_HAL::millis();
|
||||||
const uint32_t open_limit_ms = 250;
|
const uint32_t open_limit_ms = 250;
|
||||||
|
|
||||||
@ -736,7 +733,6 @@ void AP_Logger_File::PrepForArming()
|
|||||||
}
|
}
|
||||||
hal.scheduler->delay(1);
|
hal.scheduler->delay(1);
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -61,7 +61,7 @@ protected:
|
|||||||
|
|
||||||
bool WritesOK() const override;
|
bool WritesOK() const override;
|
||||||
bool StartNewLogOK() const override;
|
bool StartNewLogOK() const override;
|
||||||
void PrepForArming() override;
|
void PrepForArming_start_logging() override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
int _write_fd = -1;
|
int _write_fd = -1;
|
||||||
|
Loading…
Reference in New Issue
Block a user