diff --git a/libraries/DataFlash/DataFlash_Backend.h b/libraries/DataFlash/DataFlash_Backend.h index 308049479d..815ab184c8 100644 --- a/libraries/DataFlash/DataFlash_Backend.h +++ b/libraries/DataFlash/DataFlash_Backend.h @@ -60,7 +60,7 @@ public: void set_mission(const AP_Mission *mission); - virtual uint16_t bufferspace_available() = 0; + virtual uint32_t bufferspace_available() = 0; virtual uint16_t start_new_log(void) = 0; bool log_write_started; diff --git a/libraries/DataFlash/DataFlash_Block.cpp b/libraries/DataFlash/DataFlash_Block.cpp index e8a011f68b..41397282c3 100644 --- a/libraries/DataFlash/DataFlash_Block.cpp +++ b/libraries/DataFlash/DataFlash_Block.cpp @@ -12,11 +12,11 @@ extern AP_HAL::HAL& hal; // this if (and only if!) the low level format changes #define DF_LOGGING_FORMAT 0x28122013 -uint16_t DataFlash_Block::bufferspace_available() +uint32_t DataFlash_Block::bufferspace_available() { // because DataFlash_Block devices are ring buffers, we *always* // have room... - return df_NumPages * df_PageSize; + return df_NumPages * df_PageSize; } // *** DATAFLASH PUBLIC FUNCTIONS *** diff --git a/libraries/DataFlash/DataFlash_Block.h b/libraries/DataFlash/DataFlash_Block.h index e5ca25a0d0..e77a8b6d49 100644 --- a/libraries/DataFlash/DataFlash_Block.h +++ b/libraries/DataFlash/DataFlash_Block.h @@ -40,7 +40,7 @@ public: void ShowDeviceInfo(AP_HAL::BetterStream *port); void ListAvailableLogs(AP_HAL::BetterStream *port); - uint16_t bufferspace_available(); + uint32_t bufferspace_available(); private: struct PageHeader { diff --git a/libraries/DataFlash/DataFlash_File.cpp b/libraries/DataFlash/DataFlash_File.cpp index 462a8765a2..0ba0a74670 100644 --- a/libraries/DataFlash/DataFlash_File.cpp +++ b/libraries/DataFlash/DataFlash_File.cpp @@ -473,7 +473,7 @@ bool DataFlash_File::WritePrioritisedBlock(const void *pBuffer, uint16_t size, b return false; } - uint16_t space = _writebuf.space(); + uint32_t space = _writebuf.space(); if (_writing_startup_messages && _startup_messagewriter->fmt_done()) { diff --git a/libraries/DataFlash/DataFlash_File.h b/libraries/DataFlash/DataFlash_File.h index b44848bc69..8ca1061433 100644 --- a/libraries/DataFlash/DataFlash_File.h +++ b/libraries/DataFlash/DataFlash_File.h @@ -44,7 +44,7 @@ public: /* Write a block of data at current offset */ bool WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical); - uint16_t bufferspace_available(); + uint32_t bufferspace_available(); // high level interface uint16_t find_last_log() override; @@ -129,9 +129,9 @@ private: } return ret; }; - uint16_t non_messagewriter_message_reserved_space() const { + uint32_t non_messagewriter_message_reserved_space() const { // possibly make this a proportional to buffer size? - uint16_t ret = 1024; + uint32_t ret = 1024; if (ret >= _writebuf.get_size()) { // need to allow messages out from the messagewriters. In // this case while you have a messagewriter you won't get diff --git a/libraries/DataFlash/DataFlash_MAVLink.cpp b/libraries/DataFlash/DataFlash_MAVLink.cpp index 2f7b7ea8c7..8b258ee50c 100644 --- a/libraries/DataFlash/DataFlash_MAVLink.cpp +++ b/libraries/DataFlash/DataFlash_MAVLink.cpp @@ -55,7 +55,7 @@ bool DataFlash_MAVLink::logging_failed() const return !_sending_to_client; } -uint16_t DataFlash_MAVLink::bufferspace_available() { +uint32_t DataFlash_MAVLink::bufferspace_available() { return (_blockcount_free * 200 + remaining_space_in_current_block()); } diff --git a/libraries/DataFlash/DataFlash_MAVLink.h b/libraries/DataFlash/DataFlash_MAVLink.h index 967ef818fe..2beb241ca1 100644 --- a/libraries/DataFlash/DataFlash_MAVLink.h +++ b/libraries/DataFlash/DataFlash_MAVLink.h @@ -157,7 +157,7 @@ private: void Log_Write_DF_MAV(DataFlash_MAVLink &df); void internal_error(); - uint16_t bufferspace_available() override; // in bytes + uint32_t bufferspace_available() override; // in bytes uint8_t remaining_space_in_current_block(); // write buffer uint8_t _blockcount_free;