46 #include <px4_platform_common/log.h> 47 #include <px4_platform_common/time.h> 50 #if defined(__PX4_DARWIN) 51 #include <sys/param.h> 52 #include <sys/mount.h> 54 #include <sys/statfs.h> 57 #define GPS_EPOCH_SECS ((time_t)1234567890ULL) 71 return stat(filename, &buffer) == 0;
74 bool get_log_time(
struct tm *tt,
int utc_offset_sec,
bool boot_time)
79 bool use_clock_time =
true;
84 if (vehicle_gps_position_sub.copy(&gps_pos)) {
88 use_clock_time =
false;
94 struct timespec ts = {};
95 px4_clock_gettime(CLOCK_REALTIME, &ts);
96 utc_time_sec = ts.tv_sec + (ts.tv_nsec / 1e9);
109 utc_time_sec += utc_offset_sec;
111 return gmtime_r(&utc_time_sec, tt) !=
nullptr;
117 struct statfs statfs_buf;
119 if (max_log_dirs_to_keep == 0) {
120 max_log_dirs_to_keep = INT32_MAX;
125 if (statfs(log_root_dir, &statfs_buf) != 0) {
129 DIR *dp = opendir(log_root_dir);
135 struct dirent *result =
nullptr;
137 int num_sess = 0, num_dates = 0;
141 int year_min = 10000, month_min = 99, day_min = 99, sess_idx_min = 99999999, sess_idx_max = 0;
143 while ((result = readdir(dp))) {
144 int year, month, day, sess_idx;
146 if (sscanf(result->d_name,
"sess%d", &sess_idx) == 1) {
149 if (sess_idx > sess_idx_max) {
150 sess_idx_max = sess_idx;
153 if (sess_idx < sess_idx_min) {
154 sess_idx_min = sess_idx;
157 }
else if (sscanf(result->d_name,
"%d-%d-%d", &year, &month, &day) == 3) {
160 if (year < year_min) {
165 }
else if (year == year_min) {
166 if (month < month_min) {
170 }
else if (month == month_min) {
181 sess_dir_index = sess_idx_max + 1;
184 uint64_t min_free_bytes = 300ULL * 1024ULL * 1024ULL;
185 uint64_t total_bytes = (uint64_t)statfs_buf.f_blocks * statfs_buf.f_bsize;
187 if (total_bytes / 10 < min_free_bytes) {
188 min_free_bytes = total_bytes / 10;
191 if (num_sess + num_dates <= max_log_dirs_to_keep &&
196 if (num_sess == 0 && num_dates == 0) {
203 if (num_sess >= num_dates) {
204 n = snprintf(directory_to_delete,
sizeof(directory_to_delete),
"%s/sess%03u", log_root_dir, sess_idx_min);
207 n = snprintf(directory_to_delete,
sizeof(directory_to_delete),
"%s/%04u-%02u-%02u", log_root_dir, year_min, month_min,
211 if (n >= (
int)
sizeof(directory_to_delete)) {
212 PX4_ERR(
"log path too long (%i)", n);
216 PX4_INFO(
"removing log directory %s to get more space (left=%u MiB)", directory_to_delete,
217 (
unsigned int)(statfs_buf.f_bavail * statfs_buf.f_bsize / 1024U / 1024U));
220 PX4_ERR(
"Failed to delete directory");
230 "[logger] Not logging; SD almost full: %u MiB",
231 (
unsigned int)(statfs_buf.f_bavail * statfs_buf.f_bsize / 1024U / 1024U));
240 DIR *d = opendir(dir);
241 size_t dir_len = strlen(dir);
249 while (!ret && (p = readdir(d))) {
254 if (!strcmp(p->d_name,
".") || !strcmp(p->d_name,
"..")) {
258 len = dir_len + strlen(p->d_name) + 2;
264 snprintf(buf, len,
"%s/%s", dir, p->d_name);
266 if (!stat(buf, &statbuf)) {
267 if (S_ISDIR(statbuf.st_mode)) {
static orb_advert_t * mavlink_log_pub
#define mavlink_log_critical(_pub, _text,...)
Send a mavlink critical message and print to console.
High-resolution timer with callouts and timekeeping.
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
bool get_log_time(struct tm *tt, int utc_offset_sec, bool boot_time)
Get the time for log file name.
int remove_directory(const char *dir)
Recursively remove a directory.
decltype(statfs::f_bavail) typedef px4_statfs_buf_f_bavail_t
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
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)
Check if there is enough free space left on the SD Card.
bool file_exist(const char *filename)
check if a file exists
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).