DataFlash: don't try and open logfile on failure more than once

this prevents a corrupted microSD card from causing a continuous
attempt to open a log file while in flight, which can cause large
scheduler delays

Pair-Programmed-With: Grant Morphett <grant@gmorph.com>
This commit is contained in:
Andrew Tridgell 2014-12-21 13:31:27 +11:00
parent abd1ece6e3
commit c93ae67541
2 changed files with 30 additions and 8 deletions

View File

@ -39,6 +39,7 @@ DataFlash_File::DataFlash_File(const char *log_directory) :
_read_offset(0),
_write_offset(0),
_initialised(false),
_open_error(false),
_log_directory(log_directory),
_writebuf(NULL),
_writebuf_size(16*1024),
@ -128,7 +129,7 @@ void DataFlash_File::Init(const struct LogStructure *structure, uint8_t num_type
// return true for CardInserted() if we successfully initialised
bool DataFlash_File::CardInserted(void)
{
return _initialised;
return _initialised && !_open_error;
}
@ -195,7 +196,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 || !_writes_enabled) {
if (_write_fd == -1 || !_initialised || _open_error || !_writes_enabled) {
return;
}
uint16_t _head;
@ -232,7 +233,7 @@ void DataFlash_File::WriteBlock(const void *pBuffer, uint16_t size)
*/
void DataFlash_File::ReadBlock(void *pkt, uint16_t size)
{
if (_read_fd == -1 || !_initialised) {
if (_read_fd == -1 || !_initialised || _open_error) {
return;
}
@ -311,7 +312,7 @@ void DataFlash_File::get_log_boundaries(uint16_t log_num, uint16_t & start_page,
*/
int16_t DataFlash_File::get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)
{
if (!_initialised) {
if (!_initialised || _open_error) {
return -1;
}
if (_read_fd != -1 && log_num != _read_fd_log_num) {
@ -325,10 +326,17 @@ int16_t DataFlash_File::get_log_data(uint16_t log_num, uint16_t page, uint32_t o
}
stop_logging();
_read_fd = ::open(fname, O_RDONLY);
free(fname);
if (_read_fd == -1) {
_open_error = true;
int saved_errno = errno;
::printf("Log read open fail for %s - %s\n",
fname, strerror(saved_errno));
hal.console->printf("Log read open fail for %s - %s\n",
fname, strerror(saved_errno));
free(fname);
return -1;
}
free(fname);
_read_offset = 0;
_read_fd_log_num = log_num;
}
@ -408,6 +416,12 @@ uint16_t DataFlash_File::start_new_log(void)
{
stop_logging();
if (_open_error) {
// we have previously failed to open a file - don't try again
// to prevent us trying to open files while in flight
return 0xFFFF;
}
if (_read_fd != -1) {
::close(_read_fd);
_read_fd = -1;
@ -423,11 +437,18 @@ uint16_t DataFlash_File::start_new_log(void)
}
char *fname = _log_file_name(log_num);
_write_fd = ::open(fname, O_WRONLY|O_CREAT|O_TRUNC, 0666);
free(fname);
if (_write_fd == -1) {
_initialised = false;
_open_error = true;
int saved_errno = errno;
::printf("Log open fail for %s - %s\n",
fname, strerror(saved_errno));
hal.console->printf("Log open fail for %s - %s\n",
fname, strerror(saved_errno));
free(fname);
return 0xFFFF;
}
free(fname);
_write_offset = 0;
_writebuf_head = 0;
_writebuf_tail = 0;
@ -452,7 +473,7 @@ void DataFlash_File::LogReadProcess(uint16_t log_num,
AP_HAL::BetterStream *port)
{
uint8_t log_step = 0;
if (!_initialised) {
if (!_initialised || _open_error) {
return;
}
if (_read_fd != -1) {
@ -584,7 +605,7 @@ void DataFlash_File::ListAvailableLogs(AP_HAL::BetterStream *port)
void DataFlash_File::_io_timer(void)
{
uint16_t _tail;
if (_write_fd == -1 || !_initialised) {
if (_write_fd == -1 || !_initialised || _open_error) {
return;
}

View File

@ -58,6 +58,7 @@ private:
uint32_t _read_offset;
uint32_t _write_offset;
volatile bool _initialised;
volatile bool _open_error;
const char *_log_directory;
/*