mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-13 03:18:29 -04:00
DataFlash: create a WritesOK method for WritePrioritisedBlock
This commit is contained in:
parent
1dbf1086b0
commit
9464bc6173
@ -259,3 +259,11 @@ bool DataFlash_Backend::Log_Write(const uint8_t msg_type, va_list arg_list, bool
|
||||
|
||||
return WritePrioritisedBlock(buffer, msg_len, is_critical);
|
||||
}
|
||||
|
||||
bool DataFlash_Backend::WritesOK() const
|
||||
{
|
||||
if (!_writes_enabled) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
@ -140,6 +140,8 @@ protected:
|
||||
print_mode_fn print_mode,
|
||||
AP_HAL::BetterStream *port);
|
||||
|
||||
virtual bool WritesOK() const;
|
||||
|
||||
bool _writes_enabled = false;
|
||||
|
||||
/*
|
||||
|
@ -42,13 +42,27 @@ void DataFlash_Block::FinishWrite(void)
|
||||
df_BufferIdx = 0;
|
||||
}
|
||||
|
||||
bool DataFlash_Block::WritesOK() const
|
||||
{
|
||||
if (!DataFlash_Backend::WritesOK()) {
|
||||
return false;
|
||||
}
|
||||
if (!CardInserted()) {
|
||||
return false;
|
||||
}
|
||||
if (!log_write_started) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool DataFlash_Block::WritePrioritisedBlock(const void *pBuffer, uint16_t size,
|
||||
bool is_critical)
|
||||
{
|
||||
// is_critical is ignored - we're a ring buffer and never run out
|
||||
// of space. possibly if we do more complicated bandwidth
|
||||
// limiting we can reservice bandwidth based on is_critical
|
||||
if (!CardInserted() || !log_write_started || !_writes_enabled) {
|
||||
if (!WritesOK()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -13,7 +13,7 @@ public:
|
||||
DataFlash_Block(DataFlash_Class &front, DFMessageWriter_DFLogStart *writer) :
|
||||
DataFlash_Backend(front, writer) { }
|
||||
|
||||
virtual bool CardInserted(void) = 0;
|
||||
virtual bool CardInserted(void) const = 0;
|
||||
|
||||
// erase handling
|
||||
void EraseAll();
|
||||
@ -115,6 +115,8 @@ protected:
|
||||
uint16_t df_NumPages;
|
||||
|
||||
virtual void ReadManufacturerID() = 0;
|
||||
|
||||
bool WritesOK() const override;
|
||||
};
|
||||
|
||||
|
||||
|
@ -509,10 +509,27 @@ void DataFlash_File::EraseAll()
|
||||
}
|
||||
}
|
||||
|
||||
bool DataFlash_File::WritesOK() const
|
||||
{
|
||||
if (!DataFlash_Backend::WritesOK()) {
|
||||
return false;
|
||||
}
|
||||
if (_write_fd == -1) {
|
||||
return false;
|
||||
}
|
||||
if (!_initialised) {
|
||||
return false;
|
||||
}
|
||||
if (_open_error) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
/* Write a block of data at current offset */
|
||||
bool DataFlash_File::WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
|
||||
{
|
||||
if (_write_fd == -1 || !_initialised || _open_error || !_writes_enabled) {
|
||||
if (!WritesOK()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -73,6 +73,10 @@ public:
|
||||
|
||||
void vehicle_was_disarmed() override;
|
||||
|
||||
protected:
|
||||
|
||||
bool WritesOK() const override;
|
||||
|
||||
private:
|
||||
int _write_fd;
|
||||
int _read_fd;
|
||||
|
@ -118,12 +118,27 @@ bool DataFlash_MAVLink::free_seqno_from_queue(uint32_t seqno, dm_block_queue_t &
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
bool DataFlash_MAVLink::WritesOK() const
|
||||
{
|
||||
if (!DataFlash_Backend::WritesOK()) {
|
||||
return false;
|
||||
}
|
||||
if (!_initialised) {
|
||||
return false;
|
||||
}
|
||||
if (!_sending_to_client) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
/* Write a block of data at current offset */
|
||||
|
||||
// DM_write: 70734 events, 0 overruns, 167806us elapsed, 2us avg, min 1us max 34us 0.620us rms
|
||||
bool DataFlash_MAVLink::WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
|
||||
{
|
||||
if (!_initialised || !_sending_to_client || !_writes_enabled) {
|
||||
if (!WritesOK()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -67,6 +67,10 @@ public:
|
||||
|
||||
void remote_log_block_status_msg(mavlink_channel_t chan, mavlink_message_t* msg) override;
|
||||
|
||||
protected:
|
||||
|
||||
bool WritesOK() const override;
|
||||
|
||||
private:
|
||||
|
||||
struct dm_block {
|
||||
|
@ -55,7 +55,7 @@ void DataFlash_SITL::ReadManufacturerID()
|
||||
df_device = 0x0203;
|
||||
}
|
||||
|
||||
bool DataFlash_SITL::CardInserted(void)
|
||||
bool DataFlash_SITL::CardInserted(void) const
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
@ -42,7 +42,7 @@ public:
|
||||
DataFlash_Block(front, writer) { }
|
||||
void Init() override;
|
||||
void ReadManufacturerID();
|
||||
bool CardInserted();
|
||||
bool CardInserted() const;
|
||||
};
|
||||
|
||||
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
|
Loading…
Reference in New Issue
Block a user