Browse Source

logger: Fix calculation of total and left bytes

sbg
Jun-Tao 7 years ago committed by Lorenz Meier
parent
commit
c7cb62eb28
  1. 6
      src/modules/logger/logger.cpp

6
src/modules/logger/logger.cpp

@ -2117,7 +2117,7 @@ int Logger::check_free_space() @@ -2117,7 +2117,7 @@ int Logger::check_free_space()
uint64_t min_free_bytes = 300ULL * 1024ULL * 1024ULL;
uint64_t total_bytes = statfs_buf.f_blocks * statfs_buf.f_bsize / 10;
uint64_t total_bytes = statfs_buf.f_blocks * statfs_buf.f_bsize;
if (total_bytes / 10 < min_free_bytes) { // reduce the minimum if it's larger than 10% of the disk size
min_free_bytes = total_bytes / 10;
@ -2149,7 +2149,7 @@ int Logger::check_free_space() @@ -2149,7 +2149,7 @@ int Logger::check_free_space()
}
PX4_INFO("removing log directory %s to get more space (left=%u MiB)", directory_to_delete,
(unsigned int)(statfs_buf.f_bavail / 1024U * statfs_buf.f_bsize / 1024U));
(unsigned int)(statfs_buf.f_bavail * statfs_buf.f_bsize / 1024U / 1024U));
if (remove_directory(directory_to_delete)) {
PX4_ERR("Failed to delete directory");
@ -2163,7 +2163,7 @@ int Logger::check_free_space() @@ -2163,7 +2163,7 @@ int Logger::check_free_space()
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",
(unsigned int)(statfs_buf.f_bavail / 1024U * statfs_buf.f_bsize / 1024U));
(unsigned int)(statfs_buf.f_bavail * statfs_buf.f_bsize / 1024U / 1024U));
return 1;
}

Loading…
Cancel
Save