欢迎交流~ 个人 Gitter 交流平台,点击直达:
玩过Pixhawk看过log日志文件的朋友可能都会发现日志上显示的时间与我们实际飞行的时间不一致。
细心的应该会发现日志上记录的时间比本地时间慢了8个小时。
这是由于PX4中记录日志使用的是UTC世界统一时间。而北京处于东八区,按照东正西负的计算方法,我们需要在原有的时间上进行修改,增加一个偏移量。
param_t log_utc_offset = param_find("SDLOG_UTC_OFFSET");
if ( log_utc_offset != PARAM_INVALID ) {
int32_t param_utc_offset;
param_get(log_utc_offset, ¶m_utc_offset);
_utc_offset = param_utc_offset;
}
if (check_free_space() != OK) {
PX4_WARN("ERR: MicroSD almost full");
return 1;
}
具体修改方法如下
Firmware/src/modules/logger/params.c
关于SD卡日志记录的实现,查看sdlog2.c
上面的方法确实能修改fs/miscrosd/log文件夹下面的时间,但是SD卡根目录下的txt文件时间还是落后了8个小时的。
使用全局搜索文件名的方法找到了日志文件创建的函数
int open_log_file()
{
struct tm tt;
bool time_ok = get_log_time_tt(&tt, false); // 注意调用
/* start logging if we have a valid time and the time is not in the past */
if (log_name_timestamp && time_ok) {
strftime(log_file_name, sizeof(log_file_name), "%H_%M_%S.px4log", &tt);
snprintf(log_file_path, sizeof(log_file_path), "%s/%s", log_dir, log_file_name);
...
以及
struct tm tt;
/***
//struct tm
//{
// int tm_sec; /* second (0-61, allows for leap seconds) */
// int tm_min; /* minute (0-59) */
// int tm_hour; /* hour (0-23) */
// int tm_mday; /* day of the month (1-31) */
// int tm_mon; /* month (0-11) */
// int tm_year; /* years since 1900 */
// int tm_wday; /* day of the week (0-6) */ /*not supported by NuttX*/
// int tm_yday; /* day of the year (0-365) */ /*not supported by NuttX*/
// int tm_isdst; /* non-0 if daylight savings time is in effect */ /*not supported by NuttX*/
//};
...
strftime(tstamp, sizeof(tstamp) - 1, "%Y_%m_%d_%H_%M_%S", &tt);
...
snprintf(log_file_path, sizeof(log_file_path) - 1, PX4_ROOTFSDIR"/fs/microsd/msgs_%s.txt", tstamp);
赶时间,直接说答案了,改strftime
函数
case 'H':
{
len = snprintf(dest, chleft, "%02d", tm->tm_hour + 8);
}
break;
方法一和方法二不能重复使用,建议只用方法二
问题: 注意看后面的修改时间还是没有改变,应该是系统的boot时间。
注意到调用的get_log_time_tt(struct tm *tt, bool boot_time)
函数,所有log日志中药创建文件或文件夹之前都先调用了此函数作为时间基准。
/**
* Get the time struct from the currently preferred time source
*/
bool get_log_time_tt(struct tm *tt, bool boot_time) {
struct timespec ts;
px4_clock_gettime(CLOCK_REALTIME, &ts);
/* use RTC time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.px4log */
time_t utc_time_sec = 0;
if (_gpstime_only && has_gps_3d_fix) {
utc_time_sec = gps_time_sec;
} else {
utc_time_sec = ts.tv_sec + (ts.tv_nsec / 1e9);
}
if (utc_time_sec > PX4_EPOCH_SECS) {
/* strip the time elapsed since boot */
if (boot_time) {
utc_time_sec -= hrt_absolute_time() / 1e6;
}
/* apply utc offset (min, not hour) */
utc_time_sec += _utc_offset*60; // 前文中时差设置
struct tm *ttp = gmtime_r(&utc_time_sec, tt);// 最终时间设置源头
return (ttp != NULL);
} else {
return false;
}
}
例如创建log文件夹
int create_log_dir()
{
...
struct tm tt;
bool time_ok = get_log_time_tt(&tt, true);
...
strftime(log_dir + n, sizeof(log_dir) - n, "%Y-%m-%d", &tt);
...
int n = snprintf(log_dir, sizeof(log_dir), "%s/sess%03u", log_root, dir_number);
...
}
打开log文件
int open_log_file()
{
...
struct tm tt;
bool time_ok = get_log_time_tt(&tt, false);
...
strftime(log_file_name, sizeof(log_file_name), "%H_%M_%S.px4log", &tt);
...
snprintf(log_file_name, sizeof(log_file_name), "log%03u.px4log", file_number);
snprintf(log_file_path, sizeof(log_file_path), "%s/%s", log_dir, log_file_name);
...
}
记录表现(perf)文件
int open_perf_file(const char* str)
{
...
struct tm tt;
bool time_ok = get_log_time_tt(&tt, false);
if (log_name_timestamp && time_ok) {
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);
...
snprintf(log_file_name, sizeof(log_file_name), "perf%03u.txt", file_number);
snprintf(log_file_path, sizeof(log_file_path), "%s/%s_%s", log_dir, str, log_file_name);
...
然后在mavlink_message.cpp
里面记录的是/fs/microsd/msgs_%Y_%m_%d_%H_%M_%S".txt
这种名称的文件。其直接调用了gmtime_r()。
class MavlinkStreamStatustext : public MavlinkStream
{
public:
...
protected:
...
void send(const hrt_abstime t)
{
...
struct tm tt;
gmtime_r(&gps_time_sec, &tt);
...
...
strftime(tstamp, sizeof(tstamp) - 1, "%Y_%m_%d_%H_%M_%S", &tt);
...
snprintf(log_file_path, sizeof(log_file_path) - 1, PX4_ROOTFSDIR"/fs/microsd/msgs_%s.txt", tstamp);
....
进入gmtime_r()
函数之前,可以先了解一下1970.01.01计算机时间开始的这一天,格林威治标准时间GMT和UTC世界统一时间之间有着千丝万缕的关系。
/****************************************************************************
* Function: gmtime_r
*
* Description:
* Time conversion (based on the POSIX API)
*
****************************************************************************/
FAR struct tm *gmtime_r(FAR const time_t *timer, FAR struct tm *result)
{
time_t epoch;
time_t jdn;
int year;
int month;
int day;
int hour;
int min;
int sec;
/* Get the seconds since the EPOCH */
/* 纪元开始 */
epoch = *timer;
sdbg("timer=%d\n", (int)epoch);
/* Convert to days, hours, minutes, and seconds since the EPOCH */
jdn = epoch / SEC_PER_DAY; // 天数
epoch -= SEC_PER_DAY * jdn; // 减去 天数 * 一天的秒数
hour = epoch / SEC_PER_HOUR; // 小时数
epoch -= SEC_PER_HOUR * hour; // 减去 小时数 * 一小时的秒数
min = epoch / SEC_PER_MIN; // 分钟数
epoch -= SEC_PER_MIN * min; // 减去 分钟数 * 一分钟的秒数
sec = epoch; // 最终秒数
sdbg("hour=%d min=%d sec=%d\n",
(int)hour, (int)min, (int)sec); // 记下时分秒
/* Convert the days since the EPOCH to calendar day */
clock_utc2calendar(jdn, &year, &month, &day); // 确定日期,自1970.1.1之后的
sdbg("jdn=%d year=%d month=%d day=%d\n",
(int)jdn, (int)year, (int)month, (int)day);//记下年月日天
/* Then return the struct tm contents */
/* 老朋友tm结构体的初始值在此 */
result->tm_year = (int)year - 1900; /* Relative to 1900 */
result->tm_mon = (int)month - 1; /* zero-based */
result->tm_mday = (int)day; /* one-based */
result->tm_hour = (int)hour;
result->tm_min = (int)min;
result->tm_sec = (int)sec;
return result;
}
可见在函数的最后给tm
这个结构体赋了初值。
2017.5.3 修改
默认为50Hz
int sdlog2_thread_main(int argc, char *argv[])
{
/* default log rate: 50 Hz */
int32_t log_rate = 50;
int log_buffer_size = LOG_BUFFER_SIZE_DEFAULT;
logging_enabled = false;
/* enable logging on start (-e option) */
bool log_on_start = false;
/* enable logging when armed (-a option) */
bool log_when_armed = false;
log_name_timestamp = false;
flag_system_armed = false;
...
while ((ch = px4_getopt(argc, argv, "r:b:eatx", &myoptind, &myoptarg)) != EOF) { // 注意看这里
switch (ch) {
case 'r': {
unsigned long r = strtoul(myoptarg, NULL, 10);
if (r <= 0) {
r = 1;
}
log_rate = r;
}
break;
...
从上面这个while
循环可以看到,px4_getopt
函数接受来自命令行的传递参数,这就要看看sdlog2
函数的使用说明了:
Sdlog2的基本用法:
sdlog2 {start|stop|status|on|off} [-r ] [-b ] -e -a -t -x
-r Log rate in Hz, 0 means unlimited rate
设置记录的频率,0为不限,最好不要用,会占据很多cpu时间
-b Log buffer size in KiB, default is 8
设置缓存大小,默认为8KB,
-e Enable logging by default (if not, can be started by command)
开机自动开始记录,如果没有自动开始记录,仍然可以通过命令开始
-a Log only when armed (can be still overriden by command)
只有arm后才开始记录,可以通过命令更改。
-t Use date/time for naming log directories and files
用日期和时间命名日志文件夹和文件
-x Extended logging
拓展记录,可以记录更多的数据
也可以更改SDLOG_RATE进行设置
从rcS启动脚本中可以知道sdlog2的日志记录频率为100Hz
sdlog2 start -r 100 -a -b 9 -t
如果启动脚本不进行设置,也可以在主程序中定义
/* interpret logging params */
int32_t param_log_rate = -1;
param_t log_rate_ph = param_find("SDLOG_RATE");
if (log_rate_ph != PARAM_INVALID) {
param_get(log_rate_ph, ¶m_log_rate);
if (param_log_rate > 0) {
/* we can't do more than ~ 500 Hz, even with a massive buffer */
if (param_log_rate > 250) {
param_log_rate = 250;
}
} else if (param_log_rate == 0) {
/* we need at minimum 10 Hz to be able to see anything */
param_log_rate = 10;
}
}
// if parameter was provided use it, if not use command line argument
log_rate = param_log_rate > -1 ? param_log_rate : log_rate;
Firmware/src/modules/sdlog2/params.c
这里SDLOG_RATE的定义如下
/**
* Logging rate.
*
* A value of -1 indicates the commandline argument
* should be obeyed. A value of 0 sets the minimum rate,
* any other value is interpreted as rate in Hertz. This
* parameter is only read out before logging starts (which
* commonly is before arming).
*
* @unit Hz
* @min -1
* @max 250
* @group SD Logging
*/
PARAM_DEFINE_INT32(SDLOG_RATE, -1);
默认为-1,表示遵守命令行参数设置的速率。也可以自行设定
By Fantasy