PX4 Firmware
PX4 Autopilot Software http://px4.io
util.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2018 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 #include "util.h"
35 
36 #include <dirent.h>
37 #include <sys/stat.h>
38 #include <string.h>
39 #include <stdlib.h>
40 #include <unistd.h>
41 
42 #include <uORB/Subscription.hpp>
44 
45 #include <drivers/drv_hrt.h>
46 #include <px4_platform_common/log.h>
47 #include <px4_platform_common/time.h>
48 #include <systemlib/mavlink_log.h>
49 
50 #if defined(__PX4_DARWIN)
51 #include <sys/param.h>
52 #include <sys/mount.h>
53 #else
54 #include <sys/statfs.h>
55 #endif
56 
57 #define GPS_EPOCH_SECS ((time_t)1234567890ULL)
58 
59 typedef decltype(statfs::f_bavail) px4_statfs_buf_f_bavail_t;
60 
61 namespace px4
62 {
63 namespace logger
64 {
65 namespace util
66 {
67 
68 bool file_exist(const char *filename)
69 {
70  struct stat buffer;
71  return stat(filename, &buffer) == 0;
72 }
73 
74 bool get_log_time(struct tm *tt, int utc_offset_sec, bool boot_time)
75 {
76  uORB::Subscription vehicle_gps_position_sub{ORB_ID(vehicle_gps_position)};
77 
78  time_t utc_time_sec;
79  bool use_clock_time = true;
80 
81  /* Get the latest GPS publication */
82  vehicle_gps_position_s gps_pos;
83 
84  if (vehicle_gps_position_sub.copy(&gps_pos)) {
85  utc_time_sec = gps_pos.time_utc_usec / 1e6;
86 
87  if (gps_pos.fix_type >= 2 && utc_time_sec >= GPS_EPOCH_SECS) {
88  use_clock_time = false;
89  }
90  }
91 
92  if (use_clock_time) {
93  /* take clock time if there's no fix (yet) */
94  struct timespec ts = {};
95  px4_clock_gettime(CLOCK_REALTIME, &ts);
96  utc_time_sec = ts.tv_sec + (ts.tv_nsec / 1e9);
97 
98  if (utc_time_sec < GPS_EPOCH_SECS) {
99  return false;
100  }
101  }
102 
103  /* strip the time elapsed since boot */
104  if (boot_time) {
105  utc_time_sec -= hrt_absolute_time() / 1e6;
106  }
107 
108  /* apply utc offset */
109  utc_time_sec += utc_offset_sec;
110 
111  return gmtime_r(&utc_time_sec, tt) != nullptr;
112 }
113 
114 int check_free_space(const char *log_root_dir, int32_t max_log_dirs_to_keep, orb_advert_t &mavlink_log_pub,
115  int &sess_dir_index)
116 {
117  struct statfs statfs_buf;
118 
119  if (max_log_dirs_to_keep == 0) {
120  max_log_dirs_to_keep = INT32_MAX;
121  }
122 
123  // remove old logs if the free space falls below a threshold
124  do {
125  if (statfs(log_root_dir, &statfs_buf) != 0) {
126  return PX4_ERROR;
127  }
128 
129  DIR *dp = opendir(log_root_dir);
130 
131  if (dp == nullptr) {
132  break; // ignore if we cannot access the log directory
133  }
134 
135  struct dirent *result = nullptr;
136 
137  int num_sess = 0, num_dates = 0;
138 
139  // There are 2 directory naming schemes: sess<i> or <year>-<month>-<day>.
140  // For both we find the oldest and then remove the one which has more directories.
141  int year_min = 10000, month_min = 99, day_min = 99, sess_idx_min = 99999999, sess_idx_max = 0;
142 
143  while ((result = readdir(dp))) {
144  int year, month, day, sess_idx;
145 
146  if (sscanf(result->d_name, "sess%d", &sess_idx) == 1) {
147  ++num_sess;
148 
149  if (sess_idx > sess_idx_max) {
150  sess_idx_max = sess_idx;
151  }
152 
153  if (sess_idx < sess_idx_min) {
154  sess_idx_min = sess_idx;
155  }
156 
157  } else if (sscanf(result->d_name, "%d-%d-%d", &year, &month, &day) == 3) {
158  ++num_dates;
159 
160  if (year < year_min) {
161  year_min = year;
162  month_min = month;
163  day_min = day;
164 
165  } else if (year == year_min) {
166  if (month < month_min) {
167  month_min = month;
168  day_min = day;
169 
170  } else if (month == month_min) {
171  if (day < day_min) {
172  day_min = day;
173  }
174  }
175  }
176  }
177  }
178 
179  closedir(dp);
180 
181  sess_dir_index = sess_idx_max + 1;
182 
183 
184  uint64_t min_free_bytes = 300ULL * 1024ULL * 1024ULL;
185  uint64_t total_bytes = (uint64_t)statfs_buf.f_blocks * statfs_buf.f_bsize;
186 
187  if (total_bytes / 10 < min_free_bytes) { // reduce the minimum if it's larger than 10% of the disk size
188  min_free_bytes = total_bytes / 10;
189  }
190 
191  if (num_sess + num_dates <= max_log_dirs_to_keep &&
192  statfs_buf.f_bavail >= (px4_statfs_buf_f_bavail_t)(min_free_bytes / statfs_buf.f_bsize)) {
193  break; // enough free space and limit not reached
194  }
195 
196  if (num_sess == 0 && num_dates == 0) {
197  break; // nothing to delete
198  }
199 
200  char directory_to_delete[LOG_DIR_LEN];
201  int n;
202 
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);
205 
206  } else {
207  n = snprintf(directory_to_delete, sizeof(directory_to_delete), "%s/%04u-%02u-%02u", log_root_dir, year_min, month_min,
208  day_min);
209  }
210 
211  if (n >= (int)sizeof(directory_to_delete)) {
212  PX4_ERR("log path too long (%i)", n);
213  break;
214  }
215 
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));
218 
219  if (remove_directory(directory_to_delete)) {
220  PX4_ERR("Failed to delete directory");
221  break;
222  }
223 
224  } while (true);
225 
226 
227  /* use a threshold of 50 MiB: if below, do not start logging */
228  if (statfs_buf.f_bavail < (px4_statfs_buf_f_bavail_t)(50 * 1024 * 1024 / statfs_buf.f_bsize)) {
229  mavlink_log_critical(&mavlink_log_pub,
230  "[logger] Not logging; SD almost full: %u MiB",
231  (unsigned int)(statfs_buf.f_bavail * statfs_buf.f_bsize / 1024U / 1024U));
232  return 1;
233  }
234 
235  return PX4_OK;
236 }
237 
238 int remove_directory(const char *dir)
239 {
240  DIR *d = opendir(dir);
241  size_t dir_len = strlen(dir);
242  struct dirent *p;
243  int ret = 0;
244 
245  if (!d) {
246  return -1;
247  }
248 
249  while (!ret && (p = readdir(d))) {
250  int ret2 = -1;
251  char *buf;
252  size_t len;
253 
254  if (!strcmp(p->d_name, ".") || !strcmp(p->d_name, "..")) {
255  continue;
256  }
257 
258  len = dir_len + strlen(p->d_name) + 2;
259  buf = new char[len];
260 
261  if (buf) {
262  struct stat statbuf;
263 
264  snprintf(buf, len, "%s/%s", dir, p->d_name);
265 
266  if (!stat(buf, &statbuf)) {
267  if (S_ISDIR(statbuf.st_mode)) {
268  ret2 = remove_directory(buf);
269 
270  } else {
271  ret2 = unlink(buf);
272  }
273  }
274 
275  delete[] buf;
276  }
277 
278  ret = ret2;
279  }
280 
281  closedir(d);
282 
283  if (!ret) {
284  ret = rmdir(dir);
285  }
286 
287  return ret;
288 }
289 
290 } //namespace util
291 } //namespace logger
292 } //namespace px4
static orb_advert_t * mavlink_log_pub
#define LOG_DIR_LEN
Definition: util.h:44
High-resolution timer with callouts and timekeeping.
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
bool get_log_time(struct tm *tt, int utc_offset_sec, bool boot_time)
Get the time for log file name.
Definition: util.cpp:74
int remove_directory(const char *dir)
Recursively remove a directory.
Definition: util.cpp:238
decltype(statfs::f_bavail) typedef px4_statfs_buf_f_bavail_t
Definition: util.cpp:59
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
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.
Definition: util.cpp:114
Definition: bst.cpp:62
#define GPS_EPOCH_SECS
Definition: util.cpp:57
bool file_exist(const char *filename)
check if a file exists
Definition: util.cpp:68
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).