ulog_messages.h
Go to the documentation of this file.
00001 /****************************************************************************
00002  *
00003  *   Copyright (c) 2016 PX4 Development Team. All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions
00007  * are met:
00008  *
00009  * 1. Redistributions of source code must retain the above copyright
00010  *    notice, this list of conditions and the following disclaimer.
00011  * 2. Redistributions in binary form must reproduce the above copyright
00012  *    notice, this list of conditions and the following disclaimer in
00013  *    the documentation and/or other materials provided with the
00014  *    distribution.
00015  * 3. Neither the name PX4 nor the names of its contributors may be
00016  *    used to endorse or promote products derived from this software
00017  *    without specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00020  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00021  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00022  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00023  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00024  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00025  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
00026  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
00027  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00028  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00029  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00030  * POSSIBILITY OF SUCH DAMAGE.
00031  *
00032  ****************************************************************************/
00033 
00034 #pragma once
00035 
00036 #include <cstdint>
00037 
00038 enum class ULogMessageType : uint8_t {
00039         FORMAT = 'F',
00040         DATA = 'D',
00041         INFO = 'I',
00042         INFO_MULTIPLE = 'M',
00043         PARAMETER = 'P',
00044         ADD_LOGGED_MSG = 'A',
00045         REMOVE_LOGGED_MSG = 'R',
00046         SYNC = 'S',
00047         DROPOUT = 'O',
00048         LOGGING = 'L',
00049         FLAG_BITS = 'B',
00050 };
00051 
00052 
00053 /* declare message data structs with byte alignment (no padding) */
00054 #pragma pack(push, 1)
00055 
00057 struct ulog_file_header_s {
00058         uint8_t magic[8];
00059         uint64_t timestamp;
00060 };
00061 
00062 #define ULOG_MSG_HEADER_LEN 3 //accounts for msg_size and msg_type
00063 struct ulog_message_header_s {
00064         uint16_t msg_size;
00065         uint8_t msg_type;
00066 };
00067 
00068 struct ulog_message_format_s {
00069         uint16_t msg_size; //size of message - ULOG_MSG_HEADER_LEN
00070         uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::FORMAT);
00071 
00072         char format[1500];
00073 };
00074 
00075 struct ulog_message_add_logged_s {
00076         uint16_t msg_size; //size of message - ULOG_MSG_HEADER_LEN
00077         uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::ADD_LOGGED_MSG);
00078 
00079         uint8_t multi_id;
00080         uint16_t msg_id;
00081         char message_name[255];
00082 };
00083 
00084 struct ulog_message_remove_logged_s {
00085         uint16_t msg_size; //size of message - ULOG_MSG_HEADER_LEN
00086         uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::REMOVE_LOGGED_MSG);
00087 
00088         uint16_t msg_id;
00089 };
00090 
00091 struct ulog_message_sync_s {
00092         uint16_t msg_size; //size of message - ULOG_MSG_HEADER_LEN
00093         uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::SYNC);
00094 
00095         uint8_t sync_magic[8];
00096 };
00097 
00098 struct ulog_message_dropout_s {
00099         uint16_t msg_size = sizeof(uint16_t); //size of message - ULOG_MSG_HEADER_LEN
00100         uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::DROPOUT);
00101 
00102         uint16_t duration; //in ms
00103 };
00104 
00105 struct ulog_message_data_header_s {
00106         uint16_t msg_size; //size of message - ULOG_MSG_HEADER_LEN
00107         uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::DATA);
00108 
00109         uint16_t msg_id;
00110 };
00111 
00112 struct ulog_message_info_header_s {
00113         uint16_t msg_size; //size of message - ULOG_MSG_HEADER_LEN
00114         uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::INFO);
00115 
00116         uint8_t key_len;
00117         char key[255];
00118 };
00119 
00120 struct ulog_message_info_multiple_header_s {
00121         uint16_t msg_size; //size of message - ULOG_MSG_HEADER_LEN
00122         uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::INFO_MULTIPLE);
00123 
00124         uint8_t is_continued; 
00125         uint8_t key_len;
00126         char key[255];
00127 };
00128 
00129 struct ulog_message_logging_s {
00130         uint16_t msg_size; //size of message - ULOG_MSG_HEADER_LEN
00131         uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::LOGGING);
00132 
00133         uint8_t log_level; //same levels as in the linux kernel
00134         uint64_t timestamp;
00135         char message[128]; //defines the maximum length of a logged message string
00136 };
00137 
00138 struct ulog_message_parameter_header_s {
00139         uint16_t msg_size;
00140         uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::PARAMETER);
00141 
00142         uint8_t key_len;
00143         char key[255];
00144 };
00145 
00146 
00147 #define ULOG_INCOMPAT_FLAG0_DATA_APPENDED_MASK (1<<0)
00148 
00149 struct ulog_message_flag_bits_s {
00150         uint16_t msg_size;
00151         uint8_t msg_type = static_cast<uint8_t>(ULogMessageType::FLAG_BITS);
00152 
00153         uint8_t compat_flags[8];
00154         uint8_t incompat_flags[8]; 
00155         uint64_t appended_offsets[3]; 
00156 };
00157 
00158 #pragma pack(pop)


plotjuggler
Author(s): Davide Faconti
autogenerated on Wed Jul 3 2019 19:28:05