aboutsummaryrefslogtreecommitdiff
path: root/src/modules/sdlog2/sdlog2.c
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2015-01-04 16:14:41 +0100
committerLorenz Meier <lm@inf.ethz.ch>2015-01-04 16:14:41 +0100
commit1f181fb03f5eb467d5e1f0933164363269986844 (patch)
tree2b71ad7d8268b3e9e188b1198de5545e7a636f71 /src/modules/sdlog2/sdlog2.c
parentbccc37cfb9175cf38f2769c1654f5b7ec3a88618 (diff)
downloadpx4-firmware-1f181fb03f5eb467d5e1f0933164363269986844.tar.gz
px4-firmware-1f181fb03f5eb467d5e1f0933164363269986844.tar.bz2
px4-firmware-1f181fb03f5eb467d5e1f0933164363269986844.zip
SDLOG2: Use RTC, not GPS time for file naming
Diffstat (limited to 'src/modules/sdlog2/sdlog2.c')
-rw-r--r--src/modules/sdlog2/sdlog2.c48
1 files changed, 30 insertions, 18 deletions
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 2ce3d0097..10b6c903f 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -103,6 +103,8 @@
#include "sdlog2_format.h"
#include "sdlog2_messages.h"
+#define PX4_EPOCH_SECS 1234567890ULL
+
/**
* Logging rate.
*
@@ -338,13 +340,16 @@ int create_log_dir()
uint16_t dir_number = 1; // start with dir sess001
int mkdir_ret;
- if (log_name_timestamp && gps_time != 0) {
- /* use GPS date for log dir naming: e.g. /fs/microsd/2014-01-19 */
- time_t gps_time_sec = gps_time / 1000000;
- struct tm t;
- gmtime_r(&gps_time_sec, &t);
+ timespec ts;
+ clock_gettime(CLOCK_REALTIME, &ts);
+ /* use RTC time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.bin */
+ time_t utc_time_sec = ts.tv_sec + (ts.tv_nsec / 1e9);
+ struct tm tt;
+ struct tm *ttp = gmtime_r(&utc_time_sec, &tt);
+
+ if (log_name_timestamp && ttp && (utc_time_sec > PX4_EPOCH_SECS)) {
int n = snprintf(log_dir, sizeof(log_dir), "%s/", log_root);
- strftime(log_dir + n, sizeof(log_dir) - n, "%Y-%m-%d", &t);
+ strftime(log_dir + n, sizeof(log_dir) - n, "%Y-%m-%d", &tt);
mkdir_ret = mkdir(log_dir, S_IRWXU | S_IRWXG | S_IRWXO);
if (mkdir_ret == OK) {
@@ -395,12 +400,16 @@ int open_log_file()
char log_file_name[32] = "";
char log_file_path[64] = "";
- if (log_name_timestamp && gps_time != 0) {
- /* use GPS time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.bin */
- time_t gps_time_sec = gps_time / 1000000;
- struct tm t;
- gmtime_r(&gps_time_sec, &t);
- strftime(log_file_name, sizeof(log_file_name), "%H_%M_%S.bin", &t);
+ timespec ts;
+ clock_gettime(CLOCK_REALTIME, &ts);
+ /* use RTC time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.bin */
+ time_t utc_time_sec = ts.tv_sec + (ts.tv_nsec / 1e9);
+ struct tm tt;
+ struct tm *ttp = gmtime_r(&utc_time_sec, &tt);
+
+ /* start logging if we have a valid time and the time is not in the past */
+ if (log_name_timestamp && ttp && (utc_time_sec > PX4_EPOCH_SECS)) {
+ strftime(log_file_name, sizeof(log_file_name), "%H_%M_%S.bin", &tt);
snprintf(log_file_path, sizeof(log_file_path), "%s/%s", log_dir, log_file_name);
} else {
@@ -446,12 +455,15 @@ int open_perf_file(const char* str)
char log_file_name[32] = "";
char log_file_path[64] = "";
- if (log_name_timestamp && gps_time != 0) {
- /* use GPS time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.bin */
- time_t gps_time_sec = gps_time / 1000000;
- struct tm t;
- gmtime_r(&gps_time_sec, &t);
- strftime(log_file_name, sizeof(log_file_name), "perf%H_%M_%S.txt", &t);
+ timespec ts;
+ clock_gettime(CLOCK_REALTIME, &ts);
+ /* use RTC time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.bin */
+ time_t utc_time_sec = ts.tv_sec + (ts.tv_nsec / 1e9);
+ struct tm tt;
+ struct tm *ttp = gmtime_r(&utc_time_sec, &tt);
+
+ if (log_name_timestamp && ttp && (utc_time_sec > PX4_EPOCH_SECS)) {
+ strftime(log_file_name, sizeof(log_file_name), "perf%H_%M_%S.txt", &tt);
snprintf(log_file_path, sizeof(log_file_path), "%s/%s_%s", log_dir, str, log_file_name);
} else {