mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: Prepare the maximum number of log files in the config parameter
This commit is contained in:
parent
8cd91b4789
commit
d98a400d9e
|
@ -77,6 +77,8 @@ extern const AP_HAL::HAL& hal;
|
|||
#define LOGGING_FIRST_DYNAMIC_MSGID 254
|
||||
#endif
|
||||
|
||||
static constexpr uint16_t MAX_LOG_FILES = 500;
|
||||
static constexpr uint16_t MIN_LOG_FILES = 2;
|
||||
|
||||
const AP_Param::GroupInfo AP_Logger::var_info[] = {
|
||||
// @Param: _BACKEND_TYPE
|
||||
|
@ -176,7 +178,16 @@ const AP_Param::GroupInfo AP_Logger::var_info[] = {
|
|||
// @Increment: 0.1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_DARM_RATEMAX", 11, AP_Logger, _params.disarm_ratemax, 0),
|
||||
|
||||
|
||||
// @Param: _MAX_FILES
|
||||
// @DisplayName: Maximum number of log files
|
||||
// @Description: This sets the maximum number of log file that will be written on dataflash or sd card before starting to rotate log number. Limit is capped at 500 logs.
|
||||
// @Range: 2 500
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("_MAX_FILES", 12, AP_Logger, _params.max_log_files, MAX_LOG_FILES),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -822,6 +833,14 @@ uint16_t AP_Logger::get_num_logs(void) {
|
|||
return backends[0]->get_num_logs();
|
||||
}
|
||||
|
||||
uint16_t AP_Logger::get_max_num_logs() {
|
||||
const auto max_logs = constrain_uint16(_params.max_log_files.get(), MIN_LOG_FILES, MAX_LOG_FILES);
|
||||
if (_params.max_log_files.get() != max_logs) {
|
||||
_params.max_log_files.set_and_save_ifchanged(static_cast<int16_t>(max_logs));
|
||||
}
|
||||
return static_cast<uint16_t>(_params.max_log_files.get());
|
||||
}
|
||||
|
||||
/* we're started if any of the backends are started */
|
||||
bool AP_Logger::logging_started(void) {
|
||||
for (uint8_t i=0; i< _next_backend; i++) {
|
||||
|
|
|
@ -226,6 +226,7 @@ public:
|
|||
uint16_t find_last_log() const;
|
||||
void get_log_boundaries(uint16_t log_num, uint32_t & start_page, uint32_t & end_page);
|
||||
uint16_t get_num_logs(void);
|
||||
uint16_t get_max_num_logs();
|
||||
|
||||
void setVehicle_Startup_Writer(vehicle_startup_message_Writer writer);
|
||||
|
||||
|
@ -336,6 +337,7 @@ public:
|
|||
AP_Float mav_ratemax;
|
||||
AP_Float blk_ratemax;
|
||||
AP_Float disarm_ratemax;
|
||||
AP_Int16 max_log_files;
|
||||
} _params;
|
||||
|
||||
const struct LogStructure *structure(uint16_t num) const;
|
||||
|
|
|
@ -599,8 +599,9 @@ uint16_t AP_Logger_Backend::log_num_from_list_entry(const uint16_t list_entry)
|
|||
}
|
||||
|
||||
uint32_t log_num = oldest_log + list_entry - 1;
|
||||
if (log_num > MAX_LOG_FILES) {
|
||||
log_num -= MAX_LOG_FILES;
|
||||
const auto max_logs_num = _front.get_max_num_logs();
|
||||
if (log_num > (uint32_t)max_logs_num) {
|
||||
log_num -= max_logs_num;
|
||||
}
|
||||
return (uint16_t)log_num;
|
||||
}
|
||||
|
|
|
@ -12,8 +12,6 @@
|
|||
|
||||
class LoggerMessageWriter_DFLogStart;
|
||||
|
||||
#define MAX_LOG_FILES 500
|
||||
|
||||
// class to handle rate limiting of log messages
|
||||
class AP_Logger_RateLimiter
|
||||
{
|
||||
|
|
|
@ -234,7 +234,7 @@ bool AP_Logger_File::dirent_to_log_num(const dirent *de, uint16_t &log_num) cons
|
|||
}
|
||||
|
||||
uint16_t thisnum = strtoul(de->d_name, nullptr, 10);
|
||||
if (thisnum > MAX_LOG_FILES) {
|
||||
if (thisnum > _front.get_max_num_logs()) {
|
||||
return false;
|
||||
}
|
||||
log_num = thisnum;
|
||||
|
@ -330,7 +330,7 @@ void AP_Logger_File::Prep_MinSpace()
|
|||
if (avail >= target_free) {
|
||||
break;
|
||||
}
|
||||
if (count++ > MAX_LOG_FILES+10) {
|
||||
if (count++ > _front.get_max_num_logs() + 10) {
|
||||
// *way* too many deletions going on here. Possible internal error.
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::logger_too_many_deletions);
|
||||
break;
|
||||
|
@ -360,7 +360,7 @@ void AP_Logger_File::Prep_MinSpace()
|
|||
}
|
||||
}
|
||||
log_to_remove++;
|
||||
if (log_to_remove > MAX_LOG_FILES) {
|
||||
if (log_to_remove > _front.get_max_num_logs()) {
|
||||
log_to_remove = 1;
|
||||
}
|
||||
} while (log_to_remove != first_log_to_remove);
|
||||
|
@ -719,6 +719,7 @@ uint16_t AP_Logger_File::get_num_logs()
|
|||
// not a log filename
|
||||
continue;
|
||||
}
|
||||
|
||||
if (thisnum > high && (smallest_above_last == 0 || thisnum < smallest_above_last)) {
|
||||
smallest_above_last = thisnum;
|
||||
}
|
||||
|
@ -726,7 +727,7 @@ uint16_t AP_Logger_File::get_num_logs()
|
|||
AP::FS().closedir(d);
|
||||
if (smallest_above_last != 0) {
|
||||
// we have wrapped, add in the logs with high numbers
|
||||
ret += (MAX_LOG_FILES - smallest_above_last) + 1;
|
||||
ret += (_front.get_max_num_logs() - smallest_above_last) + 1;
|
||||
}
|
||||
|
||||
return ret;
|
||||
|
@ -826,7 +827,7 @@ void AP_Logger_File::start_new_log(void)
|
|||
if (_get_log_size(log_num) > 0 || log_num == 0) {
|
||||
log_num++;
|
||||
}
|
||||
if (log_num > MAX_LOG_FILES) {
|
||||
if (log_num > _front.get_max_num_logs()) {
|
||||
log_num = 1;
|
||||
}
|
||||
if (!write_fd_semaphore.take(1)) {
|
||||
|
@ -1115,7 +1116,7 @@ void AP_Logger_File::erase_next(void)
|
|||
free(fname);
|
||||
|
||||
erase.log_num++;
|
||||
if (erase.log_num <= MAX_LOG_FILES) {
|
||||
if (erase.log_num <= _front.get_max_num_logs()) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue