mirror of https://github.com/ArduPilot/ardupilot
DataFlash: add EnableWrites method
This method allows temporarily suspending writes to the dataflash which will be used in ArduCopter to ensure no messages are written while the copter is disarmed
This commit is contained in:
parent
4519aa8867
commit
a53d1075ec
|
@ -42,6 +42,7 @@ public:
|
|||
|
||||
/* logging methods common to all vehicles */
|
||||
uint16_t StartNewLog(void);
|
||||
void EnableWrites(bool enable) { _writes_enabled = enable; }
|
||||
void Log_Write_Format(const struct LogStructure *structure);
|
||||
void Log_Write_Parameter(const char *name, float value);
|
||||
void Log_Write_GPS(const GPS *gps, int32_t relative_alt);
|
||||
|
@ -74,6 +75,7 @@ protected:
|
|||
|
||||
const struct LogStructure *_structures;
|
||||
uint8_t _num_types;
|
||||
bool _writes_enabled;
|
||||
|
||||
/*
|
||||
read a block
|
||||
|
|
|
@ -37,7 +37,7 @@ void DataFlash_Block::FinishWrite(void)
|
|||
|
||||
void DataFlash_Block::WriteBlock(const void *pBuffer, uint16_t size)
|
||||
{
|
||||
if (!CardInserted() || !log_write_started) {
|
||||
if (!CardInserted() || !log_write_started || !_writes_enabled) {
|
||||
return;
|
||||
}
|
||||
while (size > 0) {
|
||||
|
@ -168,6 +168,7 @@ void DataFlash_Block::EraseAll()
|
|||
StartWrite(df_NumPages+1);
|
||||
uint32_t version = DF_LOGGING_FORMAT;
|
||||
log_write_started = true;
|
||||
_writes_enabled = true;
|
||||
WriteBlock(&version, sizeof(version));
|
||||
log_write_started = false;
|
||||
FinishWrite();
|
||||
|
|
|
@ -142,7 +142,7 @@ void DataFlash_File::EraseAll()
|
|||
/* Write a block of data at current offset */
|
||||
void DataFlash_File::WriteBlock(const void *pBuffer, uint16_t size)
|
||||
{
|
||||
if (_write_fd == -1 || !_initialised) {
|
||||
if (_write_fd == -1 || !_initialised || !_writes_enabled) {
|
||||
return;
|
||||
}
|
||||
uint16_t _head;
|
||||
|
|
|
@ -106,6 +106,9 @@ void DataFlash_SITL::BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr,
|
|||
const void *pHeader, uint8_t hdr_size,
|
||||
const void *pBuffer, uint16_t size)
|
||||
{
|
||||
if (!_writes_enabled) {
|
||||
return;
|
||||
}
|
||||
if (hdr_size) {
|
||||
memcpy(&buffer[BufferNum][IntPageAdr],
|
||||
pHeader,
|
||||
|
|
|
@ -13,6 +13,7 @@ void DataFlash_Class::Init(const struct LogStructure *structure, uint8_t num_typ
|
|||
{
|
||||
_num_types = num_types;
|
||||
_structures = structure;
|
||||
_writes_enabled = true;
|
||||
}
|
||||
|
||||
|
||||
|
|
Loading…
Reference in New Issue