forked from Archive/PX4-Autopilot
logger: add compressed events metadata file if it exists in the ROMFS
Allows to decode events not (yet) on main. The file is currently ~15KB.
This commit is contained in:
parent
02035d94aa
commit
dafead6f20
|
@ -90,6 +90,7 @@ add_custom_command(OUTPUT ${component_general_json} ${component_general_json}.xz
|
|||
--version-file ${PX4_BINARY_DIR}/src/lib/version/build_git_version.h
|
||||
COMMAND ${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/generate_crc.py
|
||||
${component_general_json}
|
||||
${PX4_BINARY_DIR}/events/all_events.json.xz
|
||||
--output ${component_information_header}
|
||||
DEPENDS
|
||||
generate_component_general.py
|
||||
|
|
|
@ -2,6 +2,7 @@
|
|||
|
||||
import argparse
|
||||
import os
|
||||
import hashlib
|
||||
|
||||
parser = argparse.ArgumentParser(description="""Generate the COMPONENT_INFORMATION checksums (CRC32) header file""")
|
||||
parser.add_argument('--output', metavar='checksums.h', help='output file')
|
||||
|
@ -30,6 +31,16 @@ def crc_update(buf, crc_table, crc):
|
|||
|
||||
crc_table = create_table()
|
||||
|
||||
def sha256sum(filename):
|
||||
h = hashlib.sha256()
|
||||
b = bytearray(128*1024)
|
||||
mv = memoryview(b)
|
||||
with open(filename, 'rb', buffering=0) as f:
|
||||
for n in iter(lambda : f.readinto(mv), 0):
|
||||
h.update(mv[:n])
|
||||
return h.hexdigest()
|
||||
|
||||
|
||||
with open(filename, 'w') as outfile:
|
||||
outfile.write("#pragma once\n")
|
||||
outfile.write("#include <stdint.h>\n")
|
||||
|
@ -38,10 +49,12 @@ with open(filename, 'w') as outfile:
|
|||
file_crc = 0
|
||||
for line in open(filename, "rb"):
|
||||
file_crc = crc_update(line, crc_table, file_crc)
|
||||
file_sha256 = sha256sum(filename)
|
||||
|
||||
basename = os.path.basename(filename)
|
||||
identifier = basename.split('.')[0]
|
||||
outfile.write("static constexpr uint32_t {:}_crc = {:};\n".format(identifier, file_crc))
|
||||
outfile.write("static constexpr const char *{:}_sha256 = \"{:}\";\n".format(identifier, file_sha256))
|
||||
|
||||
|
||||
outfile.write("}\n")
|
||||
|
|
|
@ -48,4 +48,5 @@ px4_add_module(
|
|||
watchdog.cpp
|
||||
DEPENDS
|
||||
version
|
||||
component_general_json # for checksums.h
|
||||
)
|
||||
|
|
|
@ -64,6 +64,7 @@
|
|||
#include <systemlib/mavlink_log.h>
|
||||
#include <replay/definitions.hpp>
|
||||
#include <version/version.h>
|
||||
#include <component_information/checksums.h>
|
||||
|
||||
//#define DBGPRINT //write status output every few seconds
|
||||
|
||||
|
@ -1416,6 +1417,7 @@ void Logger::start_log_file(LogType type)
|
|||
write_parameter_defaults(type);
|
||||
write_perf_data(true);
|
||||
write_console_output();
|
||||
write_events_file(LogType::Full);
|
||||
write_excluded_optional_topics(type);
|
||||
}
|
||||
|
||||
|
@ -1473,6 +1475,7 @@ void Logger::start_log_mavlink()
|
|||
write_parameter_defaults(LogType::Full);
|
||||
write_perf_data(true);
|
||||
write_console_output();
|
||||
write_events_file(LogType::Full);
|
||||
write_excluded_optional_topics(LogType::Full);
|
||||
write_all_add_logged_msg(LogType::Full);
|
||||
_writer.set_need_reliable_transfer(false);
|
||||
|
@ -1885,6 +1888,56 @@ void Logger::write_info_multiple(LogType type, const char *name, const char *val
|
|||
_writer.unlock();
|
||||
}
|
||||
|
||||
void Logger::write_info_multiple(LogType type, const char *name, int fd)
|
||||
{
|
||||
// Get the file length
|
||||
struct stat stat_data;
|
||||
|
||||
if (fstat(fd, &stat_data) == -1) {
|
||||
PX4_ERR("fstat failed (%i)", errno);
|
||||
return;
|
||||
}
|
||||
|
||||
const off_t file_size = stat_data.st_size;
|
||||
|
||||
ulog_message_info_multiple_s msg;
|
||||
uint8_t *buffer = reinterpret_cast<uint8_t *>(&msg);
|
||||
msg.msg_type = static_cast<uint8_t>(ULogMessageType::INFO_MULTIPLE);
|
||||
msg.is_continued = false;
|
||||
const int name_len = strlen(name);
|
||||
|
||||
int file_offset = 0;
|
||||
|
||||
while (file_offset < file_size) {
|
||||
_writer.lock();
|
||||
|
||||
const int max_format_length = 16; // accounts for "uint8_t[x] "
|
||||
int read_length = math::min(file_size - file_offset, (off_t)sizeof(msg.key_value_str) - name_len - max_format_length);
|
||||
|
||||
/* construct format key (type and name) */
|
||||
msg.key_len = snprintf(msg.key_value_str, sizeof(msg.key_value_str), "uint8_t[%i] %s", read_length, name);
|
||||
size_t msg_size = sizeof(msg) - sizeof(msg.key_value_str) + msg.key_len;
|
||||
|
||||
int ret = read(fd, &buffer[msg_size], read_length);
|
||||
|
||||
if (ret == read_length) {
|
||||
msg_size += read_length;
|
||||
msg.msg_size = msg_size - ULOG_MSG_HEADER_LEN;
|
||||
|
||||
write_message(type, buffer, msg_size);
|
||||
file_offset += ret;
|
||||
|
||||
} else {
|
||||
PX4_ERR("read failed (%i %i)", ret, errno);
|
||||
file_offset = file_size;
|
||||
}
|
||||
|
||||
msg.is_continued = true;
|
||||
_writer.unlock();
|
||||
_writer.notify();
|
||||
}
|
||||
}
|
||||
|
||||
void Logger::write_info(LogType type, const char *name, int32_t value)
|
||||
{
|
||||
write_info_template<int32_t>(type, name, value, "int32_t");
|
||||
|
@ -2275,6 +2328,25 @@ void Logger::write_changed_parameters(LogType type)
|
|||
_writer.notify();
|
||||
}
|
||||
|
||||
void Logger::write_events_file(LogType type)
|
||||
{
|
||||
int fd = open(PX4_ROOTFSDIR "/etc/extras/all_events.json.xz", O_RDONLY);
|
||||
|
||||
if (fd == -1) {
|
||||
if (errno != ENOENT) {
|
||||
PX4_ERR("open failed (%i)", errno);
|
||||
}
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
write_info_multiple(type, "metadata_events", fd);
|
||||
|
||||
close(fd);
|
||||
|
||||
write_info(type, "metadata_events_sha256", component_information::all_events_sha256);
|
||||
}
|
||||
|
||||
void Logger::ack_vehicle_command(vehicle_command_s *cmd, uint32_t result)
|
||||
{
|
||||
vehicle_command_ack_s vehicle_command_ack = {};
|
||||
|
|
|
@ -253,6 +253,7 @@ private:
|
|||
|
||||
void write_info(LogType type, const char *name, const char *value);
|
||||
void write_info_multiple(LogType type, const char *name, const char *value, bool is_continued);
|
||||
void write_info_multiple(LogType type, const char *name, int fd);
|
||||
void write_info(LogType type, const char *name, int32_t value);
|
||||
void write_info(LogType type, const char *name, uint32_t value);
|
||||
|
||||
|
@ -264,6 +265,7 @@ private:
|
|||
void write_parameter_defaults(LogType type);
|
||||
|
||||
void write_changed_parameters(LogType type);
|
||||
void write_events_file(LogType type);
|
||||
|
||||
inline bool copy_if_updated(int sub_idx, void *buffer, bool try_to_subscribe);
|
||||
|
||||
|
|
|
@ -206,7 +206,7 @@ struct ulog_message_info_multiple_s {
|
|||
|
||||
uint8_t is_continued; ///< Can be used for arrays: set to 1, if this message is part of the previous with the same key
|
||||
uint8_t key_len; ///< Length of the 'key'
|
||||
char key_value_str[255]; ///< String with the key and value information
|
||||
char key_value_str[1200]; ///< String with the key and value information
|
||||
};
|
||||
|
||||
/**
|
||||
|
|
Loading…
Reference in New Issue