ulog_messages.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2016 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 #pragma once
35 
36 #include <cstdint>
37 
38 enum class ULogMessageType : uint8_t
39 {
40  FORMAT = 'F',
41  DATA = 'D',
42  INFO = 'I',
43  INFO_MULTIPLE = 'M',
44  PARAMETER = 'P',
45  ADD_LOGGED_MSG = 'A',
46  REMOVE_LOGGED_MSG = 'R',
47  SYNC = 'S',
48  DROPOUT = 'O',
49  LOGGING = 'L',
50  FLAG_BITS = 'B',
51 };
52 
53 /* declare message data structs with byte alignment (no padding) */
54 #pragma pack(push, 1)
55 
58 {
59  uint8_t magic[8];
60  uint64_t timestamp;
61 };
62 
63 #define ULOG_MSG_HEADER_LEN 3 // accounts for msg_size and msg_type
65 {
66  uint16_t msg_size;
67  uint8_t msg_type;
68 };
69 
71 {
72  uint16_t msg_size; // size of message - ULOG_MSG_HEADER_LEN
73  uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::FORMAT);
74 
75  char format[1500];
76 };
77 
79 {
80  uint16_t msg_size; // size of message - ULOG_MSG_HEADER_LEN
81  uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::ADD_LOGGED_MSG);
82 
83  uint8_t multi_id;
84  uint16_t msg_id;
85  char message_name[255];
86 };
87 
89 {
90  uint16_t msg_size; // size of message - ULOG_MSG_HEADER_LEN
91  uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::REMOVE_LOGGED_MSG);
92 
93  uint16_t msg_id;
94 };
95 
97 {
98  uint16_t msg_size; // size of message - ULOG_MSG_HEADER_LEN
99  uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::SYNC);
100 
101  uint8_t sync_magic[8];
102 };
103 
105 {
106  uint16_t msg_size = sizeof(uint16_t); // size of message - ULOG_MSG_HEADER_LEN
107  uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::DROPOUT);
108 
109  uint16_t duration; // in ms
110 };
111 
113 {
114  uint16_t msg_size; // size of message - ULOG_MSG_HEADER_LEN
115  uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::DATA);
116 
117  uint16_t msg_id;
118 };
119 
121 {
122  uint16_t msg_size; // size of message - ULOG_MSG_HEADER_LEN
123  uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::INFO);
124 
125  uint8_t key_len;
126  char key[255];
127 };
128 
130 {
131  uint16_t msg_size; // size of message - ULOG_MSG_HEADER_LEN
132  uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::INFO_MULTIPLE);
133 
134  uint8_t is_continued;
135  uint8_t key_len;
137  char key[255];
138 };
139 
141 {
142  uint16_t msg_size; // size of message - ULOG_MSG_HEADER_LEN
143  uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::LOGGING);
144 
145  uint8_t log_level; // same levels as in the linux kernel
146  uint64_t timestamp;
147  char message[128]; // defines the maximum length of a logged message string
148 };
149 
151 {
152  uint16_t msg_size;
153  uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::PARAMETER);
154 
155  uint8_t key_len;
156  char key[255];
157 };
158 
159 #define ULOG_INCOMPAT_FLAG0_DATA_APPENDED_MASK (1 << 0)
160 
162 {
163  uint16_t msg_size;
164  uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::FLAG_BITS);
165 
166  uint8_t compat_flags[8];
167  uint8_t incompat_flags[8];
168  uint64_t appended_offsets[3];
169 };
170 
171 #pragma pack(pop)
FMT_INLINE std::basic_string< Char > format(const S &format_str, Args &&...args)
Definition: core.h:2081
ULogMessageType
Definition: ulog_messages.h:38


plotjuggler
Author(s): Davide Faconti
autogenerated on Sun Dec 6 2020 04:02:48