Browse Source

logger: add SDLOG_DIRS_MAX param to limit the max number of log directories

Disabled by default, so that logs are not deleted unexpectedly.
sbg
Beat Küng 8 years ago committed by Lorenz Meier
parent
commit
24380ae88c
  1. 18
      src/modules/logger/logger.cpp
  2. 1
      src/modules/logger/logger.h
  3. 19
      src/modules/logger/params.c

18
src/modules/logger/logger.cpp

@ -399,6 +399,7 @@ Logger::Logger(LogWriter::Backend backend, size_t buffer_size, uint32_t log_inte @@ -399,6 +399,7 @@ Logger::Logger(LogWriter::Backend backend, size_t buffer_size, uint32_t log_inte
_sdlog_mode(0)
{
_log_utc_offset = param_find("SDLOG_UTC_OFFSET");
_log_dirs_max = param_find("SDLOG_DIRS_MAX");
_sdlog_mode_handle = param_find("SDLOG_MODE");
if (poll_topic_name) {
@ -1770,6 +1771,16 @@ int Logger::check_free_space() @@ -1770,6 +1771,16 @@ int Logger::check_free_space()
{
struct statfs statfs_buf;
int32_t max_log_dirs_to_keep = 0;
if (_log_dirs_max != PARAM_INVALID) {
param_get(_log_dirs_max, &max_log_dirs_to_keep);
}
if (max_log_dirs_to_keep == 0) {
max_log_dirs_to_keep = INT32_MAX;
}
/* remove old logs if the free space falls below a threshold */
do {
if (statfs(LOG_ROOT, &statfs_buf) != 0) {
@ -1838,8 +1849,9 @@ int Logger::check_free_space() @@ -1838,8 +1849,9 @@ int Logger::check_free_space()
min_free_bytes = total_bytes / 10;
}
if (statfs_buf.f_bavail >= (px4_statfs_buf_f_bavail_t)(min_free_bytes / statfs_buf.f_bsize)) {
break; // enough free space
if (num_sess + num_dates <= max_log_dirs_to_keep &&
statfs_buf.f_bavail >= (px4_statfs_buf_f_bavail_t)(min_free_bytes / statfs_buf.f_bsize)) {
break; // enough free space and limit not reached
}
if (num_sess == 0 && num_dates == 0) {
@ -1873,7 +1885,7 @@ int Logger::check_free_space() @@ -1873,7 +1885,7 @@ int Logger::check_free_space()
} while (true);
/* use a threshold of 50 MiB */
/* use a threshold of 50 MiB: if below, do not start logging */
if (statfs_buf.f_bavail < (px4_statfs_buf_f_bavail_t)(50 * 1024 * 1024 / statfs_buf.f_bsize)) {
mavlink_log_critical(&_mavlink_log_pub,
"[logger] Not logging; SD almost full: %u MiB",

1
src/modules/logger/logger.h

@ -289,6 +289,7 @@ private: @@ -289,6 +289,7 @@ private:
uint32_t _log_interval;
const orb_metadata *_polling_topic_meta = nullptr; ///< if non-null, poll on this topic instead of sleeping
param_t _log_utc_offset;
param_t _log_dirs_max;
orb_advert_t _mavlink_log_pub = nullptr;
uint16_t _next_topic_id = 0; ///< id of next subscribed ulog topic
char *_replay_file_name = nullptr;

19
src/modules/logger/params.c

@ -69,6 +69,25 @@ PARAM_DEFINE_INT32(SDLOG_UTC_OFFSET, 0); @@ -69,6 +69,25 @@ PARAM_DEFINE_INT32(SDLOG_UTC_OFFSET, 0);
*/
PARAM_DEFINE_INT32(SDLOG_MODE, 0);
/**
* Maximum number of log directories to keep
*
* If there are more log directories than this value,
* the system will delete the oldest directories during startup.
*
* In addition, the system will delete old logs if there is not enough free space left.
* The minimum amount is 300 MB.
*
* If this is set to 0, old directories will only be removed if the free space falls below
* the minimum.
*
* @min 0
* @max 1000
* @reboot_required true
* @group SD Logging
*/
PARAM_DEFINE_INT32(SDLOG_DIRS_MAX, 0);
/**
* Log UUID
*

Loading…
Cancel
Save