mirror of https://github.com/ArduPilot/ardupilot
DataFlash: stop logging before filling SD card on PX4
Filling the SD card causes NuttX to have conniptions, including data loss and failure to boot
This commit is contained in:
parent
25bee93fcc
commit
a10cde35f5
|
@ -824,6 +824,12 @@ uint16_t DataFlash_File::start_new_log(void)
|
|||
_read_fd = -1;
|
||||
}
|
||||
|
||||
if (disk_space_avail() < _free_space_min_avail) {
|
||||
hal.console->printf("Out of space for logging\n");
|
||||
_open_error = true;
|
||||
return 0xffff;
|
||||
}
|
||||
|
||||
uint16_t log_num = find_last_log();
|
||||
// re-use empty logs if possible
|
||||
if (_get_log_size(log_num) > 0 || log_num == 0) {
|
||||
|
@ -1068,6 +1074,15 @@ void DataFlash_File::_io_timer(void)
|
|||
// least once per 2 seconds if data is available
|
||||
return;
|
||||
}
|
||||
if (tnow - _free_space_last_check_time > _free_space_check_interval) {
|
||||
_free_space_last_check_time = tnow;
|
||||
if (disk_space_avail() < _free_space_min_avail) {
|
||||
hal.console->printf("Out of space for logging\n");
|
||||
stop_logging();
|
||||
_open_error = true; // prevent logging starting again
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
hal.util->perf_begin(_perf_write);
|
||||
|
||||
|
|
|
@ -145,6 +145,13 @@ private:
|
|||
return ret;
|
||||
};
|
||||
|
||||
// free-space checks; filling up SD cards under NuttX leads to
|
||||
// corrupt filesystems which cause loss of data, failure to gather
|
||||
// data and failures-to-boot.
|
||||
uint64_t _free_space_last_check_time; // microseconds
|
||||
const uint32_t _free_space_check_interval = 1000000UL; // microseconds
|
||||
const uint32_t _free_space_min_avail = 8388608; // bytes
|
||||
|
||||
AP_HAL::Semaphore *semaphore;
|
||||
|
||||
// performance counters
|
||||
|
|
Loading…
Reference in New Issue