0.4.1
Loading...
Searching...
No Matches
UlogFileFormat.hpp
Go to the documentation of this file.
1// This file is part of INSTINCT, the INS Toolkit for Integrated
2// Navigation Concepts and Training by the Institute of Navigation of
3// the University of Stuttgart, Germany.
4//
5// This Source Code Form is subject to the terms of the Mozilla Public
6// License, v. 2.0. If a copy of the MPL was not distributed with this
7// file, You can obtain one at https://mozilla.org/MPL/2.0/.
8
9/// @file UlogFileFormat.hpp
10/// @brief List of all ulog message types
11/// @author M. Maier (marcel.maier@ins.uni-stuttgart.de)
12/// @date 2022-01-03
13/// @note See PX4 User Guide - ULog File Format (https://docs.px4.io/master/en/dev_log/ulog_file_format.html)
14
15#include <array>
16#include <cstdint>
17#include <vector>
18#include <string>
19
21{
22#ifndef __clang__
23 #pragma pack(push, 1) // Syntax for gcc for #pragma pack
24#endif
25// --------------------------------------------------------------- Header ------------------------------------------------------------------
26/// @brief The header is a fixed-size section and has the following format (16 bytes)
28{
29 std::array<char, 7> fileMagic{}; ///< identifier that contains 'U', 'L', 'o' and 'g' chars
30 char version{ 0 }; ///< ULog version (currently only 1, see https://docs.px4.io/master/en/dev_log/ulog_file_format.html)
31 uint64_t timeStamp{}; ///< denotes the start of the logging in microseconds
32};
33
34// --------------------------------------------------------- Definitions Section ---------------------------------------------------
35/// @brief The Definitions and Data sections consist of a stream of messages. Each starts with this header
37{
38 uint16_t msg_size{ 0 }; ///< size of the message in bytes without the header (hdr_size= 3 bytes)
39 char msg_type{ 0 }; ///< defines the content and is one of the following
40};
41
42/// @brief Flag bitset message. This message must be the first message, right after the header section, so that it has a fixed constant offset.
44{
45 message_header_s header; ///< msg header
46 std::array<uint8_t, 8> compat_flags{}; ///< compatible flag bits
47 std::array<uint8_t, 8> incompat_flags{}; ///< incompatible flag bits
48 std::array<uint64_t, 3> appended_offsets{}; ///< File offsets (0-based) for appended data
49};
50
51/// @brief format definition for a single (composite) type that can be logged or used in another definition as a nested type
53{
54 message_header_s header; ///< msg header
55 std::string format; ///< plain-text string with the following format: message_name:field0;field1;
56};
57
58/// @brief Information message
60{
61 message_header_s header; ///< msg header
62 uint8_t key_len{ 1 }; ///< length of 'key'
63 std::string key; ///< key, e.g. 'char[value_len] sys_name'
64 std::string value; ///< value, e.g. 'PX4'
65};
66
67/// @brief Information message multi. The same as the information message, except that there can be multiple messages with the same key (parsers store them as a list)
69{
70 message_header_s header; ///< msg header
71 uint8_t is_continued{ 0 }; ///< can be used for arrays
72 uint8_t key_len{ 0 }; ///< length of 'key'
73 std::string key; ///< key, e.g. 'char[value_len] sys_name'
74 std::string value; ///< value, e.g. 'PX4'
75};
76
77/// @brief parameter default message. If a parameter dynamically changes during runtime, this message can also be used in the Data section. The data type is restricted to: int32_t, float
79{
80 message_header_s header; ///< msg header
81 uint8_t default_types{ 0 }; ///< default types (TODO: Validate default value)
82 uint8_t key_len{ 0 }; ///< length of 'key'
83 std::string key; ///< key
84 std::string value; ///< value
85};
86
87// ------------------------------------------------------------ Data Section --------------------------------------------------------
88
89/// @brief Subscribed log message with name and ID. This must come before the first corresponding message_data_s
91{
92 message_header_s header; ///< msg header
93 uint8_t multi_id{ 0 }; ///< the same message format can have multiple instances, for example if the system has two sensors of the same type. The default and first instance must be 0
94 uint16_t msg_id{ 0 }; ///< unique id to match message_data_s data. The first use must set this to 0, then increase it. The same msg_id must not be used twice for different subscriptions, not even after unsubscribing
95 std::string msg_name; ///< message name to subscribe to. Must match one of the message_format_s definitions
96};
97
98/// @brief unsubscribe a message, to mark that it will not be logged anymore
100{
101 message_header_s header; ///< msg header
102 uint16_t msg_id{ 0 }; ///< unique id to match message_data_s data.
103};
104
105/// @brief contains logged data
107{
108 message_header_s header; ///< msg header
109 uint16_t msg_id{ 0 }; ///< unique id to match message_data_s data.
110 std::string data; ///< contains the logged binary message as defined by message_format_s
111};
112
113/// @brief Logged string message, i.e. printf output
115{
116 message_header_s header; ///< msg header
117 uint8_t log_level{ 0 }; ///< same as in the Linux kernel
118 uint64_t timestamp{ 0 }; ///< timestamp
119 std::string message; ///< log message
120};
121
122/// @brief Tagged Logged string message
124{
125 message_header_s header; ///< msg header
126 uint8_t log_level{ 0 }; ///< same as in the Linux kernel
127 uint16_t tag{ 0 }; ///< id representing source of logged message string. It could represent a process, thread or a class depending upon the system architecture.
128 uint64_t timestamp{ 0 }; ///< timestamp
129 std::string message; ///< log message
130};
131
132/// @brief tag attributes of message_logging_tagged_s
133enum class ulog_tag : uint8_t
134{
135 unassigned, ///< Unassigned
136 mavlink_handler, ///< MAVLink handler
137 ppk_handler, ///< PPK handler
138 camera_handler, ///< Camera handler
139 ptp_handler, ///< PTP handler
140 serial_handler, ///< Serial handler
141 watchdog, ///< Watchdog
142 io_service, ///< IO service
143 cbuf, ///< cbuf
144 ulg ///< ulg
145};
146
147/// @brief synchronization message so that a reader can recover from a corrupt message by searching for the next sync message
149{
150 message_header_s header; ///< msg header
151 std::array<uint8_t, 8> syncMsg{}; ///< synchronization message
152};
153
154/// @brief dropout (lost logging messages) of a given duration in ms. Dropouts can occur e.g. if the device is not fast enough
156{
157 message_header_s header; ///< msg header
158 uint16_t duration{ 0 }; ///< duration of dropout
159};
160
161#ifndef __clang__
162 #pragma pack(pop)
163#endif
164
165} // namespace NAV::vendor::pixhawk
ulog_tag
tag attributes of message_logging_tagged_s
Subscribed log message with name and ID. This must come before the first corresponding message_data_s...
uint8_t multi_id
the same message format can have multiple instances, for example if the system has two sensors of the...
std::string msg_name
message name to subscribe to. Must match one of the message_format_s definitions
uint16_t msg_id
unique id to match message_data_s data. The first use must set this to 0, then increase it....
uint16_t msg_id
unique id to match message_data_s data.
std::string data
contains the logged binary message as defined by message_format_s
message_header_s header
msg header
dropout (lost logging messages) of a given duration in ms. Dropouts can occur e.g....
format definition for a single (composite) type that can be logged or used in another definition as a...
std::string format
plain-text string with the following format: message_name:field0;field1;
The Definitions and Data sections consist of a stream of messages. Each starts with this header.
uint16_t msg_size
size of the message in bytes without the header (hdr_size= 3 bytes)
char msg_type
defines the content and is one of the following
std::string key
key, e.g. 'char[value_len] sys_name'
std::string value
value, e.g. 'PX4'
message_header_s header
msg header
Logged string message, i.e. printf output.
uint8_t log_level
same as in the Linux kernel
uint8_t log_level
same as in the Linux kernel
uint16_t tag
id representing source of logged message string. It could represent a process, thread or a class depe...
unsubscribe a message, to mark that it will not be logged anymore
uint16_t msg_id
unique id to match message_data_s data.
synchronization message so that a reader can recover from a corrupt message by searching for the next...
message_header_s header
msg header
std::array< uint8_t, 8 > syncMsg
synchronization message
The header is a fixed-size section and has the following format (16 bytes)
char version
ULog version (currently only 1, see https://docs.px4.io/master/en/dev_log/ulog_file_format....
uint64_t timeStamp
denotes the start of the logging in microseconds
std::array< char, 7 > fileMagic
identifier that contains 'U', 'L', 'o' and 'g' chars
Flag bitset message. This message must be the first message, right after the header section,...
std::array< uint8_t, 8 > incompat_flags
incompatible flag bits
std::array< uint8_t, 8 > compat_flags
compatible flag bits
std::array< uint64_t, 3 > appended_offsets
File offsets (0-based) for appended data.
Information message multi. The same as the information message, except that there can be multiple mes...
std::string key
key, e.g. 'char[value_len] sys_name'
parameter default message. If a parameter dynamically changes during runtime, this message can also b...
uint8_t default_types
default types (TODO: Validate default value)