Skip to content
Snippets Groups Projects
Commit 5eafa1b3 authored by Beat Küng's avatar Beat Küng
Browse files

refactor logger: move some independent methods into separate util file

parent b65871b4
No related branches found
No related tags found
No related merge requests found
......@@ -42,6 +42,7 @@ px4_add_module(
log_writer.cpp
log_writer_file.cpp
log_writer_mavlink.cpp
util.cpp
watchdog.cpp
DEPENDS
version
......
......@@ -49,7 +49,6 @@
#include <uORB/topics/log_message.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_command_ack.h>
#include <drivers/drv_hrt.h>
......@@ -64,17 +63,6 @@
#include <replay/definitions.hpp>
#include <version/version.h>
#if defined(__PX4_DARWIN)
#include <sys/param.h>
#include <sys/mount.h>
#else
#include <sys/statfs.h>
#endif
typedef decltype(statfs::f_bavail) px4_statfs_buf_f_bavail_t;
#define GPS_EPOCH_SECS ((time_t)1234567890ULL)
//#define DBGPRINT //write status output every few seconds
#if defined(DBGPRINT)
......@@ -824,7 +812,13 @@ void Logger::run()
}
}
if (check_free_space() == 1) {
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 (util::check_free_space(LOG_ROOT, max_log_dirs_to_keep, _mavlink_log_pub, _sess_dir_index) == 1) {
return;
}
}
......@@ -1363,20 +1357,20 @@ int Logger::create_log_dir(tm *tt)
return 0;
}
bool Logger::file_exist(const char *filename)
{
struct stat buffer;
return stat(filename, &buffer) == 0;
}
int Logger::get_log_file_name(char *file_name, size_t file_name_size)
{
tm tt = {};
bool time_ok = false;
if (_log_name_timestamp) {
int32_t utc_offset = 0;
if (_log_utc_offset != PARAM_INVALID) {
param_get(_log_utc_offset, &utc_offset);
}
/* use RTC time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.ulg */
time_ok = get_log_time(&tt, false);
time_ok = util::get_log_time(&tt, utc_offset * 60, false);
}
const char *replay_suffix = "";
......@@ -1409,7 +1403,7 @@ int Logger::get_log_file_name(char *file_name, size_t file_name_size)
snprintf(_log_file_name, sizeof(_log_file_name), "log%03u%s.ulg", file_number, replay_suffix);
snprintf(file_name, file_name_size, "%s/%s", _log_dir, _log_file_name);
if (!file_exist(file_name)) {
if (!util::file_exist(file_name)) {
break;
}
......@@ -1435,57 +1429,6 @@ void Logger::setReplayFile(const char *file_name)
_replay_file_name = strdup(file_name);
}
bool Logger::get_log_time(struct tm *tt, bool boot_time)
{
int vehicle_gps_position_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
if (vehicle_gps_position_sub < 0) {
return false;
}
/* Get the latest GPS publication */
vehicle_gps_position_s gps_pos;
time_t utc_time_sec;
bool use_clock_time = true;
if (orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_position_sub, &gps_pos) == 0) {
utc_time_sec = gps_pos.time_utc_usec / 1e6;
if (gps_pos.fix_type >= 2 && utc_time_sec >= GPS_EPOCH_SECS) {
use_clock_time = false;
}
}
orb_unsubscribe(vehicle_gps_position_sub);
if (use_clock_time) {
/* take clock time if there's no fix (yet) */
struct timespec ts = {};
px4_clock_gettime(CLOCK_REALTIME, &ts);
utc_time_sec = ts.tv_sec + (ts.tv_nsec / 1e9);
if (utc_time_sec < GPS_EPOCH_SECS) {
return false;
}
}
/* strip the time elapsed since boot */
if (boot_time) {
utc_time_sec -= hrt_absolute_time() / 1e6;
}
int32_t utc_offset = 0;
if (_log_utc_offset != PARAM_INVALID) {
param_get(_log_utc_offset, &utc_offset);
}
/* apply utc offset */
utc_time_sec += utc_offset * 60;
return gmtime_r(&utc_time_sec, tt) != nullptr;
}
void Logger::start_log_file()
{
if (_writer.is_started(LogWriter::BackendFile) || (_writer.backend() & LogWriter::BackendFile) == 0) {
......@@ -2053,187 +1996,6 @@ void Logger::write_changed_parameters()
_writer.notify();
}
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) {
return PX4_ERROR;
}
DIR *dp = opendir(LOG_ROOT);
if (dp == nullptr) {
break; // ignore if we cannot access the log directory
}
struct dirent *result = nullptr;
int num_sess = 0, num_dates = 0;
// There are 2 directory naming schemes: sess<i> or <year>-<month>-<day>.
// For both we find the oldest and then remove the one which has more directories.
int year_min = 10000, month_min = 99, day_min = 99, sess_idx_min = 99999999, sess_idx_max = 0;
while ((result = readdir(dp))) {
int year, month, day, sess_idx;
if (sscanf(result->d_name, "sess%d", &sess_idx) == 1) {
++num_sess;
if (sess_idx > sess_idx_max) {
sess_idx_max = sess_idx;
}
if (sess_idx < sess_idx_min) {
sess_idx_min = sess_idx;
}
} else if (sscanf(result->d_name, "%d-%d-%d", &year, &month, &day) == 3) {
++num_dates;
if (year < year_min) {
year_min = year;
month_min = month;
day_min = day;
} else if (year == year_min) {
if (month < month_min) {
month_min = month;
day_min = day;
} else if (month == month_min) {
if (day < day_min) {
day_min = day;
}
}
}
}
}
closedir(dp);
_sess_dir_index = sess_idx_max + 1;
uint64_t min_free_bytes = 300ULL * 1024ULL * 1024ULL;
uint64_t total_bytes = (uint64_t)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;
}
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) {
break; // nothing to delete
}
char directory_to_delete[LOG_DIR_LEN];
int n;
if (num_sess >= num_dates) {
n = snprintf(directory_to_delete, sizeof(directory_to_delete), "%s/sess%03u", LOG_ROOT, sess_idx_min);
} else {
n = snprintf(directory_to_delete, sizeof(directory_to_delete), "%s/%04u-%02u-%02u", LOG_ROOT, year_min, month_min,
day_min);
}
if (n >= (int)sizeof(directory_to_delete)) {
PX4_ERR("log path too long (%i)", n);
break;
}
PX4_INFO("removing log directory %s to get more space (left=%u MiB)", directory_to_delete,
(unsigned int)(statfs_buf.f_bavail * statfs_buf.f_bsize / 1024U / 1024U));
if (remove_directory(directory_to_delete)) {
PX4_ERR("Failed to delete directory");
break;
}
} while (true);
/* 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",
(unsigned int)(statfs_buf.f_bavail * statfs_buf.f_bsize / 1024U / 1024U));
return 1;
}
return PX4_OK;
}
int Logger::remove_directory(const char *dir)
{
DIR *d = opendir(dir);
size_t dir_len = strlen(dir);
struct dirent *p;
int ret = 0;
if (!d) {
return -1;
}
while (!ret && (p = readdir(d))) {
int ret2 = -1;
char *buf;
size_t len;
if (!strcmp(p->d_name, ".") || !strcmp(p->d_name, "..")) {
continue;
}
len = dir_len + strlen(p->d_name) + 2;
buf = new char[len];
if (buf) {
struct stat statbuf;
snprintf(buf, len, "%s/%s", dir, p->d_name);
if (!stat(buf, &statbuf)) {
if (S_ISDIR(statbuf.st_mode)) {
ret2 = remove_directory(buf);
} else {
ret2 = unlink(buf);
}
}
delete[] buf;
}
ret = ret2;
}
closedir(d);
if (!ret) {
ret = rmdir(dir);
}
return ret;
}
void Logger::ack_vehicle_command(orb_advert_t &vehicle_command_ack_pub, vehicle_command_s *cmd, uint32_t result)
{
vehicle_command_ack_s vehicle_command_ack = {};
......
......@@ -35,6 +35,7 @@
#include "log_writer.h"
#include "array.h"
#include "util.h"
#include <px4_defines.h>
#include <drivers/drv_hrt.h>
#include <uORB/Subscription.hpp>
......@@ -50,12 +51,6 @@ extern "C" __EXPORT int logger_main(int argc, char *argv[]);
#define TRY_SUBSCRIBE_INTERVAL 1000*1000 // interval in microseconds at which we try to subscribe to a topic
// if we haven't succeeded before
#ifdef __PX4_NUTTX
#define LOG_DIR_LEN 64
#else
#define LOG_DIR_LEN 256
#endif
namespace px4
{
namespace logger
......@@ -185,26 +180,11 @@ private:
*/
int create_log_dir(tm *tt);
/** recursively remove a directory
* @return 0 on success, <0 otherwise
*/
int remove_directory(const char *dir);
static bool file_exist(const char *filename);
/**
* Get log file name with directory (create it if necessary)
*/
int get_log_file_name(char *file_name, size_t file_name_size);
/**
* Check if there is enough free space left on the SD Card.
* It will remove old log files if there is not enough space,
* and if that fails return 1
* @return 0 on success, 1 if not enough space, <0 on error
*/
int check_free_space();
void start_log_file();
void stop_log_file();
......@@ -275,14 +255,6 @@ private:
*/
bool write_message(void *ptr, size_t size);
/**
* Get the time for log file name
* @param tt returned time
* @param boot_time use time when booted instead of current time
* @return true on success, false otherwise (eg. if no gps)
*/
bool get_log_time(struct tm *tt, bool boot_time = false);
/**
* Parse a file containing a list of uORB topics to log, calling add_topic for each
* @param fname name of file
......
/****************************************************************************
*
* Copyright (c) 2018 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "util.h"
#include <dirent.h>
#include <sys/stat.h>
#include <string.h>
#include <stdlib.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <drivers/drv_hrt.h>
#include <px4_log.h>
#include <px4_time.h>
#include <systemlib/mavlink_log.h>
#if defined(__PX4_DARWIN)
#include <sys/param.h>
#include <sys/mount.h>
#else
#include <sys/statfs.h>
#endif
#define GPS_EPOCH_SECS ((time_t)1234567890ULL)
typedef decltype(statfs::f_bavail) px4_statfs_buf_f_bavail_t;
namespace px4
{
namespace logger
{
namespace util
{
bool file_exist(const char *filename)
{
struct stat buffer;
return stat(filename, &buffer) == 0;
}
bool get_log_time(struct tm *tt, int utc_offset_sec, bool boot_time)
{
int vehicle_gps_position_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
if (vehicle_gps_position_sub < 0) {
return false;
}
/* Get the latest GPS publication */
vehicle_gps_position_s gps_pos;
time_t utc_time_sec;
bool use_clock_time = true;
if (orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_position_sub, &gps_pos) == 0) {
utc_time_sec = gps_pos.time_utc_usec / 1e6;
if (gps_pos.fix_type >= 2 && utc_time_sec >= GPS_EPOCH_SECS) {
use_clock_time = false;
}
}
orb_unsubscribe(vehicle_gps_position_sub);
if (use_clock_time) {
/* take clock time if there's no fix (yet) */
struct timespec ts = {};
px4_clock_gettime(CLOCK_REALTIME, &ts);
utc_time_sec = ts.tv_sec + (ts.tv_nsec / 1e9);
if (utc_time_sec < GPS_EPOCH_SECS) {
return false;
}
}
/* strip the time elapsed since boot */
if (boot_time) {
utc_time_sec -= hrt_absolute_time() / 1e6;
}
/* apply utc offset */
utc_time_sec += utc_offset_sec;
return gmtime_r(&utc_time_sec, tt) != nullptr;
}
int check_free_space(const char *log_root_dir, int32_t max_log_dirs_to_keep, orb_advert_t &mavlink_log_pub,
int &sess_dir_index)
{
struct statfs statfs_buf;
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_dir, &statfs_buf) != 0) {
return PX4_ERROR;
}
DIR *dp = opendir(log_root_dir);
if (dp == nullptr) {
break; // ignore if we cannot access the log directory
}
struct dirent *result = nullptr;
int num_sess = 0, num_dates = 0;
// There are 2 directory naming schemes: sess<i> or <year>-<month>-<day>.
// For both we find the oldest and then remove the one which has more directories.
int year_min = 10000, month_min = 99, day_min = 99, sess_idx_min = 99999999, sess_idx_max = 0;
while ((result = readdir(dp))) {
int year, month, day, sess_idx;
if (sscanf(result->d_name, "sess%d", &sess_idx) == 1) {
++num_sess;
if (sess_idx > sess_idx_max) {
sess_idx_max = sess_idx;
}
if (sess_idx < sess_idx_min) {
sess_idx_min = sess_idx;
}
} else if (sscanf(result->d_name, "%d-%d-%d", &year, &month, &day) == 3) {
++num_dates;
if (year < year_min) {
year_min = year;
month_min = month;
day_min = day;
} else if (year == year_min) {
if (month < month_min) {
month_min = month;
day_min = day;
} else if (month == month_min) {
if (day < day_min) {
day_min = day;
}
}
}
}
}
closedir(dp);
sess_dir_index = sess_idx_max + 1;
uint64_t min_free_bytes = 300ULL * 1024ULL * 1024ULL;
uint64_t total_bytes = (uint64_t)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;
}
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) {
break; // nothing to delete
}
char directory_to_delete[LOG_DIR_LEN];
int n;
if (num_sess >= num_dates) {
n = snprintf(directory_to_delete, sizeof(directory_to_delete), "%s/sess%03u", log_root_dir, sess_idx_min);
} else {
n = snprintf(directory_to_delete, sizeof(directory_to_delete), "%s/%04u-%02u-%02u", log_root_dir, year_min, month_min,
day_min);
}
if (n >= (int)sizeof(directory_to_delete)) {
PX4_ERR("log path too long (%i)", n);
break;
}
PX4_INFO("removing log directory %s to get more space (left=%u MiB)", directory_to_delete,
(unsigned int)(statfs_buf.f_bavail * statfs_buf.f_bsize / 1024U / 1024U));
if (remove_directory(directory_to_delete)) {
PX4_ERR("Failed to delete directory");
break;
}
} while (true);
/* 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",
(unsigned int)(statfs_buf.f_bavail * statfs_buf.f_bsize / 1024U / 1024U));
return 1;
}
return PX4_OK;
}
int remove_directory(const char *dir)
{
DIR *d = opendir(dir);
size_t dir_len = strlen(dir);
struct dirent *p;
int ret = 0;
if (!d) {
return -1;
}
while (!ret && (p = readdir(d))) {
int ret2 = -1;
char *buf;
size_t len;
if (!strcmp(p->d_name, ".") || !strcmp(p->d_name, "..")) {
continue;
}
len = dir_len + strlen(p->d_name) + 2;
buf = new char[len];
if (buf) {
struct stat statbuf;
snprintf(buf, len, "%s/%s", dir, p->d_name);
if (!stat(buf, &statbuf)) {
if (S_ISDIR(statbuf.st_mode)) {
ret2 = remove_directory(buf);
} else {
ret2 = unlink(buf);
}
}
delete[] buf;
}
ret = ret2;
}
closedir(d);
if (!ret) {
ret = rmdir(dir);
}
return ret;
}
} //namespace util
} //namespace logger
} //namespace px4
/****************************************************************************
*
* Copyright (c) 2018 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include <stdint.h>
#include <time.h>
#include <uORB/uORB.h>
#ifdef __PX4_NUTTX
#define LOG_DIR_LEN 64
#else
#define LOG_DIR_LEN 256
#endif
namespace px4
{
namespace logger
{
namespace util
{
/**
* Recursively remove a directory
* @return 0 on success, <0 otherwise
*/
int remove_directory(const char *dir);
/**
* check if a file exists
*/
bool file_exist(const char *filename);
/**
* Check if there is enough free space left on the SD Card.
* It will remove old log files if there is not enough space,
* and if that fails return 1, and send a user message
* @param log_root_dir log root directory: it's expected to contain directories in the form of sess%i or %d-%d-%d (year, month, day)
* @param max_log_dirs_to_keep maximum log directories to keep (set to 0 for unlimited)
* @param mavlink_log_pub
* @param sess_dir_index output argument: will be set to the next free directory sess%i index.
* @return 0 on success, 1 if not enough space, <0 on error
*/
int check_free_space(const char *log_root_dir, int32_t max_log_dirs_to_keep, orb_advert_t &mavlink_log_pub,
int &sess_dir_index);
/**
* Get the time for log file name
* @param tt returned time
* @param utc_offset_sec UTC time offset [s]
* @param boot_time use time when booted instead of current time
* @return true on success, false otherwise (eg. if no gps)
*/
bool get_log_time(struct tm *tt, int utc_offset_sec = 0, bool boot_time = false);
} //namespace util
} //namespace logger
} //namespace px4
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment