mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-02 02:34:06 +08:00
logger: clean up emission of events
This commit is contained in:
parent
ff7c636065
commit
39b894a014
@ -26,5 +26,5 @@ param set SDLOG_PROFILE 3
|
||||
# apply all params before ekf starts, as some params cannot be changed after startup
|
||||
replay tryapplyparams
|
||||
ekf2 start -r
|
||||
logger start -f -t -b 1000 -p vehicle_attitude
|
||||
logger start -f -b 1000 -p vehicle_attitude
|
||||
replay start
|
||||
|
||||
@ -31,5 +31,5 @@ fi
|
||||
|
||||
if ! param compare SDLOG_MODE -1
|
||||
then
|
||||
logger start -b ${LOGGER_BUF} -t ${LOGGER_ARGS}
|
||||
logger start -b ${LOGGER_BUF} ${LOGGER_ARGS}
|
||||
fi
|
||||
|
||||
@ -256,7 +256,6 @@ Logger *Logger::instantiate(int argc, char *argv[])
|
||||
int log_buffer_size = 12 * 1024;
|
||||
Logger::LogMode log_mode = Logger::LogMode::while_armed;
|
||||
bool error_flag = false;
|
||||
bool log_name_timestamp = false;
|
||||
LogWriter::Backend backend = LogWriter::BackendAll;
|
||||
const char *poll_topic = nullptr;
|
||||
|
||||
@ -313,11 +312,6 @@ Logger *Logger::instantiate(int argc, char *argv[])
|
||||
}
|
||||
break;
|
||||
|
||||
case 't':
|
||||
log_name_timestamp = true;
|
||||
break;
|
||||
|
||||
|
||||
case 'm':
|
||||
if (!strcmp(myoptarg, "file")) {
|
||||
backend = LogWriter::BackendFile;
|
||||
@ -354,7 +348,7 @@ Logger *Logger::instantiate(int argc, char *argv[])
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
Logger *logger = new Logger(backend, log_buffer_size, log_interval, poll_topic, log_mode, log_name_timestamp,
|
||||
Logger *logger = new Logger(backend, log_buffer_size, log_interval, poll_topic, log_mode,
|
||||
rate_factor);
|
||||
|
||||
#if defined(DBGPRINT) && defined(__PX4_NUTTX)
|
||||
@ -383,10 +377,9 @@ Logger *Logger::instantiate(int argc, char *argv[])
|
||||
}
|
||||
|
||||
Logger::Logger(LogWriter::Backend backend, size_t buffer_size, uint32_t log_interval, const char *poll_topic_name,
|
||||
LogMode log_mode, bool log_name_timestamp, float rate_factor) :
|
||||
LogMode log_mode, float rate_factor) :
|
||||
ModuleParams(nullptr),
|
||||
_log_mode(log_mode),
|
||||
_log_name_timestamp(log_name_timestamp),
|
||||
_event_subscription(ORB_ID::event),
|
||||
_writer(backend, buffer_size),
|
||||
_log_interval(log_interval),
|
||||
@ -1241,6 +1234,9 @@ int Logger::create_log_dir(LogType type, tm *tt, char *log_dir, int log_dir_len)
|
||||
if (tt) {
|
||||
strftime(file_name.log_dir, sizeof(LogFileName::log_dir), "%Y-%m-%d", tt);
|
||||
strncpy(log_dir + n, file_name.log_dir, log_dir_len - n);
|
||||
|
||||
PX4_INFO("creating log dir: %s", log_dir);
|
||||
|
||||
int mkdir_ret = mkdir(log_dir, S_IRWXU | S_IRWXG | S_IRWXO);
|
||||
|
||||
if (mkdir_ret != OK && errno != EEXIST) {
|
||||
@ -1287,15 +1283,17 @@ int Logger::create_log_dir(LogType type, tm *tt, char *log_dir, int log_dir_len)
|
||||
return strlen(log_dir);
|
||||
}
|
||||
|
||||
int Logger::get_log_file_name(LogType type, char *file_name, size_t file_name_size, bool notify)
|
||||
int Logger::get_log_file_name(LogType type, char *file_name, size_t file_name_size)
|
||||
{
|
||||
tm tt = {};
|
||||
bool time_ok = false;
|
||||
// We use RTC time for log file naming, e.g. /fs/microsd/log/2014-01-19/19_37_52.ulg
|
||||
|
||||
if (_log_name_timestamp) {
|
||||
/* use RTC time for log file naming, e.g. /fs/microsd/log/2014-01-19/19_37_52.ulg */
|
||||
time_ok = util::get_log_time(&tt, _param_sdlog_utc_offset.get() * 60, false);
|
||||
}
|
||||
time_t timestamp_utc = {};
|
||||
struct timespec ts = {};
|
||||
px4_clock_gettime(CLOCK_REALTIME, &ts);
|
||||
timestamp_utc = ts.tv_sec + (ts.tv_nsec / 1e9);
|
||||
|
||||
tm tt = {};
|
||||
gmtime_r(×tamp_utc, &tt);
|
||||
|
||||
const char *replay_suffix = "";
|
||||
|
||||
@ -1314,35 +1312,27 @@ int Logger::get_log_file_name(LogType type, char *file_name, size_t file_name_si
|
||||
|
||||
char *log_file_name = _file_name[(int)type].log_file_name;
|
||||
|
||||
if (time_ok) {
|
||||
// Check if time is non-zero for valid UTC timestamp
|
||||
if (timestamp_utc > 0) {
|
||||
|
||||
// TODO: move create_log_dir outside of this...
|
||||
int n = create_log_dir(type, &tt, file_name, file_name_size);
|
||||
|
||||
if (n < 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Create log file name from timestamp
|
||||
char log_file_name_time[16] = "";
|
||||
strftime(log_file_name_time, sizeof(log_file_name_time), "%H_%M_%S", &tt);
|
||||
snprintf(log_file_name, sizeof(LogFileName::log_file_name), "%s%s.ulg%s", log_file_name_time, replay_suffix,
|
||||
crypto_suffix);
|
||||
snprintf(log_file_name, sizeof(LogFileName::log_file_name), "%s%s.ulg%s", log_file_name_time, replay_suffix, crypto_suffix);
|
||||
PX4_INFO("log_file_name: %s", log_file_name);
|
||||
|
||||
// Now we copy it into some other buffer... why?
|
||||
snprintf(file_name + n, file_name_size - n, "/%s", log_file_name);
|
||||
|
||||
if (notify) {
|
||||
mavlink_log_info(&_mavlink_log_pub, "[logger] %s\t", file_name);
|
||||
uint16_t year = 0;
|
||||
uint8_t month = 0;
|
||||
uint8_t day = 0;
|
||||
sscanf(_file_name[(int)type].log_dir, "%hd-%hhd-%hhd", &year, &month, &day);
|
||||
uint8_t hour = 0;
|
||||
uint8_t minute = 0;
|
||||
uint8_t second = 0;
|
||||
sscanf(log_file_name_time, "%hhd_%hhd_%hhd", &hour, &minute, &second);
|
||||
events::send<uint16_t, uint8_t, uint8_t, uint8_t, uint8_t, uint8_t>(events::ID("logger_open_file_time"),
|
||||
events::Log::Info,
|
||||
"logging: opening log file {1}-{2}-{3}/{4}_{5}_{6}.ulg", year, month, day, hour, minute, second);
|
||||
}
|
||||
|
||||
} else {
|
||||
// TODO: move create_log_dir outside of this...
|
||||
int n = create_log_dir(type, nullptr, file_name, file_name_size);
|
||||
|
||||
if (n < 0) {
|
||||
@ -1369,16 +1359,6 @@ int Logger::get_log_file_name(LogType type, char *file_name, size_t file_name_si
|
||||
/* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (notify) {
|
||||
mavlink_log_info(&_mavlink_log_pub, "[logger] %s\t", file_name);
|
||||
uint16_t sess = 0;
|
||||
sscanf(_file_name[(int)type].log_dir, "sess%hd", &sess);
|
||||
uint16_t index = 0;
|
||||
sscanf(log_file_name, "log%hd", &index);
|
||||
events::send<uint16_t, uint16_t>(events::ID("logger_open_file_sess"), events::Log::Info,
|
||||
"logging: opening log file sess{1}/log{2}.ulg", sess, index);
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
@ -1409,11 +1389,13 @@ void Logger::start_log_file(LogType type)
|
||||
|
||||
char file_name[LOG_DIR_LEN] = "";
|
||||
|
||||
if (get_log_file_name(type, file_name, sizeof(file_name), type == LogType::Full)) {
|
||||
if (get_log_file_name(type, file_name, sizeof(file_name)) != PX4_OK) {
|
||||
PX4_ERR("failed to get log file name");
|
||||
return;
|
||||
}
|
||||
|
||||
// TODO: create log dir after getting filename
|
||||
|
||||
#if defined(PX4_CRYPTO)
|
||||
_writer.set_encryption_parameters(
|
||||
(px4_crypto_algorithm_t)_param_sdlog_crypto_algorithm.get(),
|
||||
@ -1421,6 +1403,44 @@ void Logger::start_log_file(LogType type)
|
||||
_param_sdlog_crypto_exchange_key.get());
|
||||
#endif
|
||||
|
||||
// Emit event when we're recording a full log type (TODO: rename "full" to "normal"?)
|
||||
// TODO: do we really need separate events? If the intent is to convey the full log string
|
||||
// it isn't quite right since the zeroes get dropped, see below:
|
||||
// PX4: 2025-04-05/14_27_49.ulg
|
||||
// MAVSDK : 2025-4-5/14_27_49.ulg
|
||||
if (type == LogType::Full) {
|
||||
// Check if we're using time-based format by checking for hyphen
|
||||
if (strstr(_file_name[(int)type].log_dir, "-")) {
|
||||
|
||||
// TODO: this way of populating the file_name is weird, especially since we already have it above
|
||||
uint16_t year = 0;
|
||||
uint8_t month = 0, day = 0;
|
||||
sscanf(_file_name[(int)type].log_dir, "%hd-%hhd-%hhd", &year, &month, &day);
|
||||
|
||||
uint8_t hour = 0, minute = 0, second = 0;
|
||||
sscanf(_file_name[(int)type].log_file_name, "%hhd_%hhd_%hhd", &hour, &minute, &second);
|
||||
|
||||
events::send<uint16_t, uint8_t, uint8_t, uint8_t, uint8_t, uint8_t>(
|
||||
events::ID("logger_open_file_time"),
|
||||
events::Log::Info,
|
||||
"logging: opening log file {1}-{2}-{3}/{4}_{5}_{6}.ulg",
|
||||
year, month, day, hour, minute, second);
|
||||
} else {
|
||||
// Session-based format
|
||||
uint16_t sess = 0;
|
||||
sscanf(_file_name[(int)type].log_dir, "sess%hd", &sess);
|
||||
|
||||
uint16_t log_index = 0;
|
||||
sscanf(_file_name[(int)type].log_file_name, "log%hd", &log_index);
|
||||
|
||||
events::send<uint16_t, uint16_t>(
|
||||
events::ID("logger_open_file_sess"),
|
||||
events::Log::Info,
|
||||
"logging: opening log file sess{1}/log{2}.ulg",
|
||||
sess, log_index);
|
||||
}
|
||||
}
|
||||
|
||||
if (_writer.start_log_file(type, file_name)) {
|
||||
_writer.select_write_backend(LogWriter::BackendFile);
|
||||
_writer.set_need_reliable_transfer(true);
|
||||
|
||||
@ -107,7 +107,7 @@ public:
|
||||
|
||||
|
||||
Logger(LogWriter::Backend backend, size_t buffer_size, uint32_t log_interval, const char *poll_topic_name,
|
||||
LogMode log_mode, bool log_name_timestamp, float rate_factor);
|
||||
LogMode log_mode, float rate_factor);
|
||||
|
||||
~Logger();
|
||||
|
||||
@ -211,7 +211,7 @@ private:
|
||||
/**
|
||||
* Get log file name with directory (create it if necessary)
|
||||
*/
|
||||
int get_log_file_name(LogType type, char *file_name, size_t file_name_size, bool notify);
|
||||
int get_log_file_name(LogType type, char *file_name, size_t file_name_size);
|
||||
|
||||
void start_log_file(LogType type);
|
||||
|
||||
@ -350,7 +350,6 @@ private:
|
||||
hrt_abstime _last_sync_time{0}; ///< last time a sync msg was sent
|
||||
|
||||
LogMode _log_mode;
|
||||
const bool _log_name_timestamp;
|
||||
|
||||
LoggerSubscription *_subscriptions{nullptr}; ///< all subscriptions for full & mission log (in front)
|
||||
int _num_subscriptions{0};
|
||||
|
||||
@ -55,8 +55,6 @@
|
||||
#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
|
||||
@ -72,46 +70,6 @@ bool file_exist(const char *filename)
|
||||
return stat(filename, &buffer) == 0;
|
||||
}
|
||||
|
||||
bool get_log_time(struct tm *tt, int utc_offset_sec, bool boot_time)
|
||||
{
|
||||
uORB::Subscription vehicle_gps_position_sub{ORB_ID(vehicle_gps_position)};
|
||||
|
||||
time_t utc_time_sec;
|
||||
bool use_clock_time = true;
|
||||
|
||||
/* Get the latest GPS publication */
|
||||
sensor_gps_s gps_pos;
|
||||
|
||||
if (vehicle_gps_position_sub.copy(&gps_pos)) {
|
||||
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;
|
||||
}
|
||||
}
|
||||
|
||||
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)
|
||||
{
|
||||
|
||||
@ -75,15 +75,6 @@ bool file_exist(const char *filename);
|
||||
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
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user