mirror of https://github.com/ArduPilot/ardupilot
DataFlash: add PrepForArming method
This commit is contained in:
parent
31083653b2
commit
1f0a14ab33
|
@ -321,6 +321,11 @@ bool DataFlash_Class::should_log(const uint32_t mask) const
|
|||
} \
|
||||
} while (0)
|
||||
|
||||
void DataFlash_Class::PrepForArming()
|
||||
{
|
||||
FOR_EACH_BACKEND(PrepForArming());
|
||||
}
|
||||
|
||||
void DataFlash_Class::setVehicle_Startup_Log_Writer(vehicle_startup_message_Log_Writer writer)
|
||||
{
|
||||
_vehicle_messages = writer;
|
||||
|
|
|
@ -101,6 +101,8 @@ public:
|
|||
|
||||
void setVehicle_Startup_Log_Writer(vehicle_startup_message_Log_Writer writer);
|
||||
|
||||
void PrepForArming();
|
||||
|
||||
void EnableWrites(bool enable) { _writes_enabled = enable; }
|
||||
bool WritesEnabled() const { return _writes_enabled; }
|
||||
|
||||
|
|
|
@ -59,6 +59,8 @@ public:
|
|||
|
||||
virtual uint32_t bufferspace_available() = 0;
|
||||
|
||||
virtual void PrepForArming() { }
|
||||
|
||||
virtual uint16_t start_new_log(void) = 0;
|
||||
bool log_write_started;
|
||||
|
||||
|
|
|
@ -835,6 +835,13 @@ void DataFlash_File::stop_logging(void)
|
|||
}
|
||||
}
|
||||
|
||||
void DataFlash_File::PrepForArming()
|
||||
{
|
||||
if (logging_started()) {
|
||||
return;
|
||||
}
|
||||
start_new_log();
|
||||
}
|
||||
|
||||
/*
|
||||
start writing to a new log file
|
||||
|
|
|
@ -73,6 +73,8 @@ public:
|
|||
|
||||
void vehicle_was_disarmed() override;
|
||||
|
||||
virtual void PrepForArming() override;
|
||||
|
||||
protected:
|
||||
|
||||
bool WritesOK() const override;
|
||||
|
|
Loading…
Reference in New Issue