mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-10 06:39:25 +08:00
fix(logger): add MiB unit to SDLOG_MAX_SIZE (#27245)
This required to add MiB as a unit to the parsers. While at it, I decided to clean up the MB log output and be correct using MiB instead.
This commit is contained in:
@@ -365,7 +365,7 @@ class SourceParser(object):
|
||||
allowedUnits = set ([
|
||||
'%', 'Hz', '1/s', 'mAh',
|
||||
'rad', '%/rad', 'rad/s', 'rad/s^2', '%/rad/s', 'rad s^2/m', 'rad s/m',
|
||||
'bit/s', 'B/s',
|
||||
'bit/s', 'B/s', 'MiB',
|
||||
'deg', 'deg*1e7', 'deg/s', 'deg/s^2',
|
||||
'celcius', 'gauss', 'gauss/s', 'gauss^2', 'liters',
|
||||
'hPa', 'kg', 'kg/m^2', 'kg m^2', 'kg/m^3',
|
||||
|
||||
@@ -1439,11 +1439,11 @@ void Logger::start_log_file(LogType type)
|
||||
}
|
||||
|
||||
if (type == LogType::Full) {
|
||||
int32_t max_size_mb = _param_sdlog_max_size.get();
|
||||
int32_t max_size_mib = _param_sdlog_max_size.get();
|
||||
|
||||
if (max_size_mb > 0) {
|
||||
_max_log_file_size = (size_t)max_size_mb * 1024ULL * 1024ULL;
|
||||
PX4_INFO("Max log file size: %" PRId32 " MB", max_size_mb);
|
||||
if (max_size_mib > 0) {
|
||||
_max_log_file_size = (size_t)max_size_mib * 1024ULL * 1024ULL;
|
||||
PX4_INFO("Max log file size: %" PRId32 " MiB", max_size_mib);
|
||||
|
||||
} else {
|
||||
_max_log_file_size = 0; // unlimited
|
||||
@@ -1457,7 +1457,7 @@ void Logger::start_log_file(LogType type)
|
||||
hrt_abstime cleanup_start = hrt_absolute_time();
|
||||
|
||||
if (util::cleanup_old_logs(LOG_ROOT[(int)LogType::Full], _mavlink_log_pub,
|
||||
(uint32_t)_param_sdlog_rotate.get(), (uint32_t)max_size_mb,
|
||||
(uint32_t)_param_sdlog_rotate.get(), (uint32_t)max_size_mib,
|
||||
_param_sdlog_dirs_max.get()) == 1) {
|
||||
return; // Not enough space even after cleanup
|
||||
}
|
||||
|
||||
@@ -105,16 +105,17 @@ parameters:
|
||||
SDLOG_MAX_SIZE:
|
||||
description:
|
||||
short: Maximum log file size
|
||||
long: 'Maximum size of a single log file in megabytes. When reached,
|
||||
the log file is closed and a new one is started. This value is also
|
||||
added to the cleanup threshold (see SDLOG_ROTATE) to reserve headroom
|
||||
for the next log file. A value of 0 disables both file rotation and
|
||||
the cleanup reservation.
|
||||
long: 'Maximum size of a single log file in mebibytes (1 MiB = 1024 * 1024
|
||||
bytes). When reached, the log file is closed and a new one is started.
|
||||
This value is also added to the cleanup threshold (see SDLOG_ROTATE) to
|
||||
reserve headroom for the next log file. A value of 0 disables both file
|
||||
rotation and the cleanup reservation.
|
||||
Must stay below the FAT32 file size limit of 4 GiB.'
|
||||
type: int32
|
||||
default: 1024
|
||||
min: 0
|
||||
max: 4095
|
||||
unit: MiB
|
||||
reboot_required: false
|
||||
SDLOG_ROTATE:
|
||||
description:
|
||||
|
||||
@@ -139,7 +139,7 @@ bool scan_log_directories(const char *log_root_dir, LogDirInfo &info)
|
||||
}
|
||||
|
||||
int cleanup_old_logs(const char *log_root_dir, orb_advert_t &mavlink_log_pub,
|
||||
uint32_t rotate_pct, uint32_t max_file_size_mb,
|
||||
uint32_t rotate_pct, uint32_t max_file_size_mib,
|
||||
int32_t max_dirs_to_keep)
|
||||
{
|
||||
uint64_t avail_bytes = 0;
|
||||
@@ -159,7 +159,7 @@ int cleanup_old_logs(const char *log_root_dir, orb_advert_t &mavlink_log_pub,
|
||||
|
||||
if (rotate_pct > 0 && rotate_pct <= 100) {
|
||||
cleanup_threshold = (total_bytes * (100 - rotate_pct)) / 100;
|
||||
cleanup_threshold += (uint64_t)max_file_size_mb * 1024ULL * 1024ULL;
|
||||
cleanup_threshold += (uint64_t)max_file_size_mib * 1024ULL * 1024ULL;
|
||||
}
|
||||
|
||||
bool need_space_cleanup = avail_bytes < cleanup_threshold;
|
||||
|
||||
@@ -98,14 +98,14 @@ bool scan_log_directories(const char *log_root_dir, LogDirInfo &info);
|
||||
* @param mavlink_log_pub mavlink log publisher
|
||||
* @param rotate_pct maximum disk usage percentage (0 disables space-based
|
||||
* cleanup; 90 keeps at least 10% free during writing)
|
||||
* @param max_file_size_mb maximum log file size in MB; reserved as headroom
|
||||
* for the next log file write
|
||||
* @param max_file_size_mib maximum log file size in MiB; reserved as headroom
|
||||
* for the next log file write
|
||||
* @param max_dirs_to_keep maximum number of log directories to keep (0 to
|
||||
* disable count-based cleanup)
|
||||
* @return 0 on success, 1 if not enough space even after cleanup
|
||||
*/
|
||||
int cleanup_old_logs(const char *log_root_dir, orb_advert_t &mavlink_log_pub,
|
||||
uint32_t rotate_pct, uint32_t max_file_size_mb,
|
||||
uint32_t rotate_pct, uint32_t max_file_size_mib,
|
||||
int32_t max_dirs_to_keep);
|
||||
|
||||
/**
|
||||
|
||||
Reference in New Issue
Block a user