2016-02-17 21:25:53 -04:00
|
|
|
#pragma once
|
2015-11-05 19:50:54 -04:00
|
|
|
|
2019-06-04 03:38:51 -03:00
|
|
|
// if you add any new types, units or multipliers, please update README.md
|
|
|
|
|
2015-11-05 19:50:54 -04:00
|
|
|
/*
|
2019-06-04 03:28:01 -03:00
|
|
|
Format characters in the format string for binary log messages
|
|
|
|
a : int16_t[32]
|
|
|
|
b : int8_t
|
|
|
|
B : uint8_t
|
|
|
|
h : int16_t
|
|
|
|
H : uint16_t
|
|
|
|
i : int32_t
|
|
|
|
I : uint32_t
|
|
|
|
f : float
|
|
|
|
d : double
|
|
|
|
n : char[4]
|
|
|
|
N : char[16]
|
|
|
|
Z : char[64]
|
|
|
|
c : int16_t * 100
|
|
|
|
C : uint16_t * 100
|
|
|
|
e : int32_t * 100
|
|
|
|
E : uint32_t * 100
|
|
|
|
L : int32_t latitude/longitude
|
|
|
|
M : uint8_t flight mode
|
|
|
|
q : int64_t
|
|
|
|
Q : uint64_t
|
2015-11-05 19:50:54 -04:00
|
|
|
*/
|
2015-12-07 20:51:46 -04:00
|
|
|
|
|
|
|
struct UnitStructure {
|
|
|
|
const char ID;
|
2018-02-22 05:38:58 -04:00
|
|
|
const char *unit;
|
2015-12-07 20:51:46 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
struct MultiplierStructure {
|
|
|
|
const char ID;
|
|
|
|
const double multiplier;
|
|
|
|
};
|
|
|
|
|
|
|
|
// all units here should be base units
|
|
|
|
// This does mean battery capacity is here as "amp*second"
|
2017-09-17 18:47:11 -03:00
|
|
|
// Please keep the names consistent with Tools/autotest/param_metadata/param.py:33
|
2015-12-07 20:51:46 -04:00
|
|
|
const struct UnitStructure log_Units[] = {
|
2017-09-17 18:47:11 -03:00
|
|
|
{ '-', "" }, // no units e.g. Pi, or a string
|
|
|
|
{ '?', "UNKNOWN" }, // Units which haven't been worked out yet....
|
|
|
|
{ 'A', "A" }, // Ampere
|
|
|
|
{ 'd', "deg" }, // of the angular variety, -180 to 180
|
|
|
|
{ 'b', "B" }, // bytes
|
|
|
|
{ 'k', "deg/s" }, // degrees per second. Degrees are NOT SI, but is some situations more user-friendly than radians
|
|
|
|
{ 'D', "deglatitude" }, // degrees of latitude
|
|
|
|
{ 'e', "deg/s/s" }, // degrees per second per second. Degrees are NOT SI, but is some situations more user-friendly than radians
|
|
|
|
{ 'E', "rad/s" }, // radians per second
|
|
|
|
{ 'G', "Gauss" }, // Gauss is not an SI unit, but 1 tesla = 10000 gauss so a simple replacement is not possible here
|
|
|
|
{ 'h', "degheading" }, // 0.? to 359.?
|
|
|
|
{ 'i', "A.s" }, // Ampere second
|
2017-12-05 05:54:11 -04:00
|
|
|
{ 'J', "W.s" }, // Joule (Watt second)
|
2017-09-17 18:47:11 -03:00
|
|
|
// { 'l', "l" }, // litres
|
|
|
|
{ 'L', "rad/s/s" }, // radians per second per second
|
|
|
|
{ 'm', "m" }, // metres
|
|
|
|
{ 'n', "m/s" }, // metres per second
|
|
|
|
// { 'N', "N" }, // Newton
|
|
|
|
{ 'o', "m/s/s" }, // metres per second per second
|
|
|
|
{ 'O', "degC" }, // degrees Celsius. Not SI, but Kelvin is too cumbersome for most users
|
2018-02-05 19:31:43 -04:00
|
|
|
{ '%', "%" }, // percent
|
2017-09-17 18:47:11 -03:00
|
|
|
{ 'S', "satellites" }, // number of satellites
|
|
|
|
{ 's', "s" }, // seconds
|
|
|
|
{ 'q', "rpm" }, // rounds per minute. Not SI, but sometimes more intuitive than Hertz
|
|
|
|
{ 'r', "rad" }, // radians
|
|
|
|
{ 'U', "deglongitude" }, // degrees of longitude
|
|
|
|
{ 'u', "ppm" }, // pulses per minute
|
|
|
|
{ 'v', "V" }, // Volt
|
|
|
|
{ 'P', "Pa" }, // Pascal
|
|
|
|
{ 'w', "Ohm" }, // Ohm
|
2019-07-04 22:07:54 -03:00
|
|
|
// { 'W', "Watt" }, // Watt
|
2018-10-14 01:45:42 -03:00
|
|
|
{ 'Y', "us" }, // pulse width modulation in microseconds
|
2019-02-06 22:15:41 -04:00
|
|
|
{ 'z', "Hz" }, // Hertz
|
|
|
|
{ '#', "instance" } // (e.g.)Sensor instance number
|
2015-12-07 20:51:46 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
// this multiplier information applies to the raw value present in the
|
|
|
|
// log. Any adjustment implied by the format field (e.g. the "centi"
|
|
|
|
// in "centidegrees" is *IGNORED* for the purposes of scaling.
|
|
|
|
// Essentially "format" simply tells you the C-type, and format-type h
|
|
|
|
// (int16_t) is equivalent to format-type c (int16_t*100)
|
|
|
|
// tl;dr a GCS shouldn't/mustn't infer any scaling from the unit name
|
|
|
|
|
|
|
|
const struct MultiplierStructure log_Multipliers[] = {
|
2018-01-24 19:20:12 -04:00
|
|
|
{ '-', 0 }, // no multiplier e.g. a string
|
|
|
|
{ '?', 1 }, // multipliers which haven't been worked out yet....
|
2018-02-22 05:38:58 -04:00
|
|
|
// <leave a gap here, just in case....>
|
2015-12-07 20:51:46 -04:00
|
|
|
{ '2', 1e2 },
|
|
|
|
{ '1', 1e1 },
|
|
|
|
{ '0', 1e0 },
|
|
|
|
{ 'A', 1e-1 },
|
|
|
|
{ 'B', 1e-2 },
|
|
|
|
{ 'C', 1e-3 },
|
|
|
|
{ 'D', 1e-4 },
|
|
|
|
{ 'E', 1e-5 },
|
|
|
|
{ 'F', 1e-6 },
|
|
|
|
{ 'G', 1e-7 },
|
|
|
|
// <leave a gap here, just in case....>
|
2017-09-17 18:47:11 -03:00
|
|
|
{ '!', 3.6 }, // (ampere*second => milliampere*hour) and (km/h => m/s)
|
2017-12-05 05:54:11 -04:00
|
|
|
{ '/', 3600 }, // (ampere*second => ampere*hour)
|
2015-12-07 20:51:46 -04:00
|
|
|
};
|
|
|
|
|
2019-06-04 03:28:01 -03:00
|
|
|
/*
|
|
|
|
unfortunately these need to be macros because of a limitation of
|
|
|
|
named member structure initialisation in g++
|
|
|
|
*/
|
|
|
|
#define LOG_PACKET_HEADER uint8_t head1, head2, msgid;
|
|
|
|
#define LOG_PACKET_HEADER_INIT(id) head1 : HEAD_BYTE1, head2 : HEAD_BYTE2, msgid : id
|
|
|
|
#define LOG_PACKET_HEADER_LEN 3 // bytes required for LOG_PACKET_HEADER
|
|
|
|
|
|
|
|
// once the logging code is all converted we will remove these from
|
|
|
|
// this header
|
|
|
|
#define HEAD_BYTE1 0xA3 // Decimal 163
|
|
|
|
#define HEAD_BYTE2 0x95 // Decimal 149
|
|
|
|
|
|
|
|
// structure used to define logging format
|
|
|
|
struct LogStructure {
|
|
|
|
uint8_t msg_type;
|
|
|
|
uint8_t msg_len;
|
|
|
|
const char *name;
|
|
|
|
const char *format;
|
|
|
|
const char *labels;
|
|
|
|
const char *units;
|
|
|
|
const char *multipliers;
|
|
|
|
};
|
|
|
|
|
|
|
|
// maximum lengths of fields in LogStructure, including trailing nulls
|
|
|
|
static const uint8_t LS_NAME_SIZE = 5;
|
|
|
|
static const uint8_t LS_FORMAT_SIZE = 17;
|
|
|
|
static const uint8_t LS_LABELS_SIZE = 65;
|
|
|
|
static const uint8_t LS_UNITS_SIZE = 17;
|
|
|
|
static const uint8_t LS_MULTIPLIERS_SIZE = 17;
|
|
|
|
|
|
|
|
/*
|
|
|
|
log structures common to all vehicle types
|
|
|
|
*/
|
|
|
|
struct PACKED log_Format {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint8_t type;
|
|
|
|
uint8_t length;
|
|
|
|
char name[4];
|
|
|
|
char format[16];
|
|
|
|
char labels[64];
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_Unit {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
char type;
|
|
|
|
char unit[64]; // you know, this might be overkill...
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_Format_Multiplier {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
char type;
|
|
|
|
double multiplier;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_Format_Units {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t format_type;
|
|
|
|
char units[16];
|
|
|
|
char multipliers[16];
|
|
|
|
};
|
|
|
|
|
2015-11-05 19:50:54 -04:00
|
|
|
struct PACKED log_Parameter {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
char name[16];
|
|
|
|
float value;
|
|
|
|
};
|
|
|
|
|
2017-08-25 04:18:26 -03:00
|
|
|
struct PACKED log_DSF {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint32_t dropped;
|
|
|
|
uint16_t blocks;
|
|
|
|
uint32_t bytes;
|
|
|
|
uint32_t buf_space_min;
|
|
|
|
uint32_t buf_space_max;
|
|
|
|
uint32_t buf_space_avg;
|
|
|
|
};
|
|
|
|
|
2019-02-01 07:29:43 -04:00
|
|
|
struct PACKED log_Event {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t id;
|
|
|
|
};
|
2019-03-24 22:04:59 -03:00
|
|
|
|
|
|
|
struct PACKED log_Error {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t sub_system;
|
|
|
|
uint8_t error_code;
|
|
|
|
};
|
|
|
|
|
2015-11-05 19:50:54 -04:00
|
|
|
struct PACKED log_GPS {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t status;
|
|
|
|
uint32_t gps_week_ms;
|
|
|
|
uint16_t gps_week;
|
|
|
|
uint8_t num_sats;
|
|
|
|
uint16_t hdop;
|
|
|
|
int32_t latitude;
|
|
|
|
int32_t longitude;
|
|
|
|
int32_t altitude;
|
2016-05-04 21:23:34 -03:00
|
|
|
float ground_speed;
|
2016-05-04 22:21:34 -03:00
|
|
|
float ground_course;
|
2015-11-05 19:50:54 -04:00
|
|
|
float vel_z;
|
2017-05-28 04:12:50 -03:00
|
|
|
float yaw;
|
2015-11-05 19:50:54 -04:00
|
|
|
uint8_t used;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_GPA {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint16_t vdop;
|
|
|
|
uint16_t hacc;
|
|
|
|
uint16_t vacc;
|
|
|
|
uint16_t sacc;
|
2019-09-03 16:40:48 -03:00
|
|
|
float yaw_accuracy;
|
2016-05-04 22:21:34 -03:00
|
|
|
uint8_t have_vv;
|
2016-05-05 03:03:59 -03:00
|
|
|
uint32_t sample_ms;
|
2017-07-08 20:06:47 -03:00
|
|
|
uint16_t delta_ms;
|
2015-11-05 19:50:54 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_Message {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
char msg[64];
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_IMU {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
float gyro_x, gyro_y, gyro_z;
|
|
|
|
float accel_x, accel_y, accel_z;
|
|
|
|
uint32_t gyro_error, accel_error;
|
|
|
|
float temperature;
|
|
|
|
uint8_t gyro_health, accel_health;
|
2017-05-01 00:00:46 -03:00
|
|
|
uint16_t gyro_rate, accel_rate;
|
2015-11-05 19:50:54 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_IMUDT {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
2016-04-26 02:50:29 -03:00
|
|
|
float delta_time, delta_vel_dt, delta_ang_dt;
|
2015-11-05 19:50:54 -04:00
|
|
|
float delta_ang_x, delta_ang_y, delta_ang_z;
|
|
|
|
float delta_vel_x, delta_vel_y, delta_vel_z;
|
|
|
|
};
|
|
|
|
|
2017-09-01 08:05:16 -03:00
|
|
|
struct PACKED log_ISBH {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint16_t seqno;
|
|
|
|
uint8_t sensor_type; // e.g. GYRO or ACCEL
|
|
|
|
uint8_t instance;
|
|
|
|
uint16_t multiplier;
|
2017-10-10 20:36:04 -03:00
|
|
|
uint16_t sample_count;
|
2017-09-01 08:05:16 -03:00
|
|
|
uint64_t sample_us;
|
|
|
|
float sample_rate_hz;
|
|
|
|
};
|
|
|
|
static_assert(sizeof(log_ISBH) < 256, "log_ISBH is over-size");
|
|
|
|
|
|
|
|
struct PACKED log_ISBD {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint16_t isb_seqno;
|
|
|
|
uint16_t seqno; // seqno within isb_seqno
|
|
|
|
int16_t x[32];
|
|
|
|
int16_t y[32];
|
|
|
|
int16_t z[32];
|
|
|
|
};
|
|
|
|
static_assert(sizeof(log_ISBD) < 256, "log_ISBD is over-size");
|
|
|
|
|
2015-11-05 19:50:54 -04:00
|
|
|
struct PACKED log_Vibe {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
float vibe_x, vibe_y, vibe_z;
|
|
|
|
uint32_t clipping_0, clipping_1, clipping_2;
|
|
|
|
};
|
|
|
|
|
2016-01-04 18:49:11 -04:00
|
|
|
struct PACKED log_Gimbal1 {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint32_t time_ms;
|
|
|
|
float delta_time;
|
|
|
|
float delta_angles_x;
|
|
|
|
float delta_angles_y;
|
|
|
|
float delta_angles_z;
|
|
|
|
float delta_velocity_x;
|
|
|
|
float delta_velocity_y;
|
|
|
|
float delta_velocity_z;
|
|
|
|
float joint_angles_x;
|
|
|
|
float joint_angles_y;
|
|
|
|
float joint_angles_z;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_Gimbal2 {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint32_t time_ms;
|
|
|
|
uint8_t est_sta;
|
|
|
|
float est_x;
|
|
|
|
float est_y;
|
|
|
|
float est_z;
|
|
|
|
float rate_x;
|
|
|
|
float rate_y;
|
|
|
|
float rate_z;
|
|
|
|
float target_x;
|
|
|
|
float target_y;
|
|
|
|
float target_z;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_Gimbal3 {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint32_t time_ms;
|
|
|
|
int16_t rl_torque_cmd;
|
|
|
|
int16_t el_torque_cmd;
|
|
|
|
int16_t az_torque_cmd;
|
|
|
|
};
|
|
|
|
|
2015-11-05 19:50:54 -04:00
|
|
|
struct PACKED log_RCIN {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint16_t chan1;
|
|
|
|
uint16_t chan2;
|
|
|
|
uint16_t chan3;
|
|
|
|
uint16_t chan4;
|
|
|
|
uint16_t chan5;
|
|
|
|
uint16_t chan6;
|
|
|
|
uint16_t chan7;
|
|
|
|
uint16_t chan8;
|
|
|
|
uint16_t chan9;
|
|
|
|
uint16_t chan10;
|
|
|
|
uint16_t chan11;
|
|
|
|
uint16_t chan12;
|
|
|
|
uint16_t chan13;
|
|
|
|
uint16_t chan14;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_RCOUT {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint16_t chan1;
|
|
|
|
uint16_t chan2;
|
|
|
|
uint16_t chan3;
|
|
|
|
uint16_t chan4;
|
|
|
|
uint16_t chan5;
|
|
|
|
uint16_t chan6;
|
|
|
|
uint16_t chan7;
|
|
|
|
uint16_t chan8;
|
|
|
|
uint16_t chan9;
|
|
|
|
uint16_t chan10;
|
|
|
|
uint16_t chan11;
|
|
|
|
uint16_t chan12;
|
2016-06-06 00:42:03 -03:00
|
|
|
uint16_t chan13;
|
|
|
|
uint16_t chan14;
|
2015-11-05 19:50:54 -04:00
|
|
|
};
|
|
|
|
|
2019-02-06 22:30:09 -04:00
|
|
|
struct PACKED log_MAV {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t chan;
|
|
|
|
uint16_t packet_tx_count;
|
|
|
|
uint16_t packet_rx_success_count;
|
|
|
|
uint16_t packet_rx_drop_count;
|
|
|
|
};
|
|
|
|
|
2015-11-05 19:50:54 -04:00
|
|
|
struct PACKED log_RSSI {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
float RXRSSI;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_BARO {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
float altitude;
|
|
|
|
float pressure;
|
|
|
|
int16_t temperature;
|
|
|
|
float climbrate;
|
2016-05-04 21:35:59 -03:00
|
|
|
uint32_t sample_time_ms;
|
2016-05-13 17:01:43 -03:00
|
|
|
float drift_offset;
|
2017-03-24 02:00:22 -03:00
|
|
|
float ground_temp;
|
2019-07-30 21:07:34 -03:00
|
|
|
uint8_t healthy;
|
2015-11-05 19:50:54 -04:00
|
|
|
};
|
|
|
|
|
2018-09-02 09:27:58 -03:00
|
|
|
struct PACKED log_Optflow {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t surface_quality;
|
|
|
|
float flow_x;
|
|
|
|
float flow_y;
|
|
|
|
float body_x;
|
|
|
|
float body_y;
|
|
|
|
};
|
|
|
|
|
2015-11-05 19:50:54 -04:00
|
|
|
struct PACKED log_AHRS {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
int16_t roll;
|
|
|
|
int16_t pitch;
|
|
|
|
uint16_t yaw;
|
|
|
|
float alt;
|
|
|
|
int32_t lat;
|
|
|
|
int32_t lng;
|
2017-04-15 08:19:36 -03:00
|
|
|
float q1, q2, q3, q4;
|
2015-11-05 19:50:54 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_POS {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
int32_t lat;
|
|
|
|
int32_t lng;
|
|
|
|
float alt;
|
2017-01-30 15:09:58 -04:00
|
|
|
float rel_home_alt;
|
|
|
|
float rel_origin_alt;
|
2015-11-05 19:50:54 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_POWR {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
2016-06-02 17:55:05 -03:00
|
|
|
float Vcc;
|
|
|
|
float Vservo;
|
2015-11-05 19:50:54 -04:00
|
|
|
uint16_t flags;
|
2018-04-12 20:49:48 -03:00
|
|
|
uint8_t safety_and_arm;
|
2015-11-05 19:50:54 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_EKF1 {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
int16_t roll;
|
|
|
|
int16_t pitch;
|
|
|
|
uint16_t yaw;
|
|
|
|
float velN;
|
|
|
|
float velE;
|
|
|
|
float velD;
|
|
|
|
float posD_dot;
|
|
|
|
float posN;
|
|
|
|
float posE;
|
|
|
|
float posD;
|
|
|
|
int16_t gyrX;
|
|
|
|
int16_t gyrY;
|
|
|
|
int16_t gyrZ;
|
2017-05-29 22:59:55 -03:00
|
|
|
int32_t originHgt;
|
2015-11-05 19:50:54 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_EKF2 {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
int8_t Ratio;
|
|
|
|
int8_t AZ1bias;
|
|
|
|
int8_t AZ2bias;
|
|
|
|
int16_t windN;
|
|
|
|
int16_t windE;
|
|
|
|
int16_t magN;
|
|
|
|
int16_t magE;
|
|
|
|
int16_t magD;
|
|
|
|
int16_t magX;
|
|
|
|
int16_t magY;
|
|
|
|
int16_t magZ;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_NKF2 {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
int8_t AZbias;
|
|
|
|
int16_t scaleX;
|
|
|
|
int16_t scaleY;
|
|
|
|
int16_t scaleZ;
|
|
|
|
int16_t windN;
|
|
|
|
int16_t windE;
|
|
|
|
int16_t magN;
|
|
|
|
int16_t magE;
|
|
|
|
int16_t magD;
|
|
|
|
int16_t magX;
|
|
|
|
int16_t magY;
|
|
|
|
int16_t magZ;
|
|
|
|
uint8_t index;
|
|
|
|
};
|
|
|
|
|
2016-07-14 02:08:43 -03:00
|
|
|
struct PACKED log_NKF2a {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
int16_t accBiasX;
|
|
|
|
int16_t accBiasY;
|
|
|
|
int16_t accBiasZ;
|
|
|
|
int16_t windN;
|
|
|
|
int16_t windE;
|
|
|
|
int16_t magN;
|
|
|
|
int16_t magE;
|
|
|
|
int16_t magD;
|
|
|
|
int16_t magX;
|
|
|
|
int16_t magY;
|
|
|
|
int16_t magZ;
|
|
|
|
uint8_t index;
|
|
|
|
};
|
|
|
|
|
2015-11-05 19:50:54 -04:00
|
|
|
struct PACKED log_EKF3 {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
int16_t innovVN;
|
|
|
|
int16_t innovVE;
|
|
|
|
int16_t innovVD;
|
|
|
|
int16_t innovPN;
|
|
|
|
int16_t innovPE;
|
|
|
|
int16_t innovPD;
|
|
|
|
int16_t innovMX;
|
|
|
|
int16_t innovMY;
|
|
|
|
int16_t innovMZ;
|
|
|
|
int16_t innovVT;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_NKF3 {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
int16_t innovVN;
|
|
|
|
int16_t innovVE;
|
|
|
|
int16_t innovVD;
|
|
|
|
int16_t innovPN;
|
|
|
|
int16_t innovPE;
|
|
|
|
int16_t innovPD;
|
|
|
|
int16_t innovMX;
|
|
|
|
int16_t innovMY;
|
|
|
|
int16_t innovMZ;
|
|
|
|
int16_t innovYaw;
|
|
|
|
int16_t innovVT;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_EKF4 {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
int16_t sqrtvarV;
|
|
|
|
int16_t sqrtvarP;
|
|
|
|
int16_t sqrtvarH;
|
|
|
|
int16_t sqrtvarMX;
|
|
|
|
int16_t sqrtvarMY;
|
|
|
|
int16_t sqrtvarMZ;
|
|
|
|
int16_t sqrtvarVT;
|
|
|
|
int8_t offsetNorth;
|
|
|
|
int8_t offsetEast;
|
2016-05-10 03:07:56 -03:00
|
|
|
uint16_t faults;
|
2015-11-05 19:50:54 -04:00
|
|
|
uint8_t timeouts;
|
|
|
|
uint16_t solution;
|
|
|
|
uint16_t gps;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_NKF4 {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
int16_t sqrtvarV;
|
|
|
|
int16_t sqrtvarP;
|
|
|
|
int16_t sqrtvarH;
|
|
|
|
int16_t sqrtvarM;
|
|
|
|
int16_t sqrtvarVT;
|
|
|
|
float tiltErr;
|
|
|
|
int8_t offsetNorth;
|
|
|
|
int8_t offsetEast;
|
2016-05-10 03:07:56 -03:00
|
|
|
uint16_t faults;
|
2015-11-05 19:50:54 -04:00
|
|
|
uint8_t timeouts;
|
|
|
|
uint16_t solution;
|
|
|
|
uint16_t gps;
|
|
|
|
int8_t primary;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_EKF5 {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t normInnov;
|
|
|
|
int16_t FIX;
|
|
|
|
int16_t FIY;
|
|
|
|
int16_t AFI;
|
|
|
|
int16_t HAGL;
|
|
|
|
int16_t offset;
|
|
|
|
int16_t RI;
|
|
|
|
uint16_t meaRng;
|
|
|
|
uint16_t errHAGL;
|
2016-07-03 19:11:03 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_NKF5 {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t normInnov;
|
|
|
|
int16_t FIX;
|
|
|
|
int16_t FIY;
|
|
|
|
int16_t AFI;
|
|
|
|
int16_t HAGL;
|
|
|
|
int16_t offset;
|
|
|
|
int16_t RI;
|
|
|
|
uint16_t meaRng;
|
|
|
|
uint16_t errHAGL;
|
2016-06-30 21:44:36 -03:00
|
|
|
float angErr;
|
|
|
|
float velErr;
|
|
|
|
float posErr;
|
2015-11-05 19:50:54 -04:00
|
|
|
};
|
|
|
|
|
2017-04-15 07:37:00 -03:00
|
|
|
struct PACKED log_Quaternion {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
float q1;
|
|
|
|
float q2;
|
|
|
|
float q3;
|
|
|
|
float q4;
|
|
|
|
};
|
|
|
|
|
2016-11-23 08:04:51 -04:00
|
|
|
struct PACKED log_RngBcnDebug {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t ID; // beacon identifier
|
|
|
|
int16_t rng; // beacon range (cm)
|
|
|
|
int16_t innov; // beacon range innovation (cm)
|
|
|
|
uint16_t sqrtInnovVar; // sqrt of beacon range innovation variance (cm)
|
|
|
|
uint16_t testRatio; // beacon range innovation consistency test ratio *100
|
|
|
|
int16_t beaconPosN; // beacon north position (cm)
|
|
|
|
int16_t beaconPosE; // beacon east position (cm)
|
|
|
|
int16_t beaconPosD; // beacon down position (cm)
|
|
|
|
int16_t offsetHigh; // high estimate of vertical position offset of beacons rel to EKF origin (cm)
|
|
|
|
int16_t offsetLow; // low estimate of vertical position offset of beacons rel to EKF origin (cm)
|
2016-12-17 06:00:57 -04:00
|
|
|
int16_t posN; // North position of receiver rel to EKF origin (cm)
|
|
|
|
int16_t posE; // East position of receiver rel to EKF origin (cm)
|
|
|
|
int16_t posD; // Down position of receiver rel to EKF origin (cm)
|
2016-11-23 08:04:51 -04:00
|
|
|
};
|
|
|
|
|
2017-04-03 23:47:04 -03:00
|
|
|
// visual odometry sensor data
|
|
|
|
struct PACKED log_VisualOdom {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
float time_delta;
|
|
|
|
float angle_delta_x;
|
|
|
|
float angle_delta_y;
|
|
|
|
float angle_delta_z;
|
|
|
|
float position_delta_x;
|
|
|
|
float position_delta_y;
|
|
|
|
float position_delta_z;
|
|
|
|
float confidence;
|
|
|
|
};
|
|
|
|
|
2017-03-22 00:46:33 -03:00
|
|
|
struct PACKED log_ekfBodyOdomDebug {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
float velInnovX;
|
|
|
|
float velInnovY;
|
|
|
|
float velInnovZ;
|
|
|
|
float velInnovVarX;
|
|
|
|
float velInnovVarY;
|
|
|
|
float velInnovVarZ;
|
|
|
|
};
|
|
|
|
|
2017-05-20 23:13:08 -03:00
|
|
|
struct PACKED log_ekfStateVar {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
float v00;
|
|
|
|
float v01;
|
|
|
|
float v02;
|
|
|
|
float v03;
|
|
|
|
float v04;
|
|
|
|
float v05;
|
|
|
|
float v06;
|
|
|
|
float v07;
|
|
|
|
float v08;
|
|
|
|
float v09;
|
|
|
|
float v10;
|
|
|
|
float v11;
|
|
|
|
};
|
|
|
|
|
2015-11-05 19:50:54 -04:00
|
|
|
struct PACKED log_Cmd {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint16_t command_total;
|
|
|
|
uint16_t sequence;
|
|
|
|
uint16_t command;
|
|
|
|
float param1;
|
|
|
|
float param2;
|
|
|
|
float param3;
|
|
|
|
float param4;
|
2018-11-24 23:10:07 -04:00
|
|
|
int32_t latitude;
|
|
|
|
int32_t longitude;
|
2015-11-05 19:50:54 -04:00
|
|
|
float altitude;
|
2018-03-15 15:39:51 -03:00
|
|
|
uint8_t frame;
|
2015-11-05 19:50:54 -04:00
|
|
|
};
|
|
|
|
|
2019-08-22 22:21:39 -03:00
|
|
|
struct PACKED log_MAVLink_Command {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t target_system;
|
|
|
|
uint8_t target_component;
|
|
|
|
uint8_t frame;
|
|
|
|
uint16_t command;
|
|
|
|
uint8_t current;
|
|
|
|
uint8_t autocontinue;
|
|
|
|
float param1;
|
|
|
|
float param2;
|
|
|
|
float param3;
|
|
|
|
float param4;
|
|
|
|
int32_t x;
|
|
|
|
int32_t y;
|
|
|
|
float z;
|
|
|
|
uint8_t result;
|
|
|
|
bool was_command_long;
|
|
|
|
};
|
|
|
|
|
2015-11-05 19:50:54 -04:00
|
|
|
struct PACKED log_Radio {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t rssi;
|
|
|
|
uint8_t remrssi;
|
|
|
|
uint8_t txbuf;
|
|
|
|
uint8_t noise;
|
|
|
|
uint8_t remnoise;
|
|
|
|
uint16_t rxerrors;
|
|
|
|
uint16_t fixed;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_Camera {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint32_t gps_time;
|
|
|
|
uint16_t gps_week;
|
|
|
|
int32_t latitude;
|
|
|
|
int32_t longitude;
|
|
|
|
int32_t altitude;
|
|
|
|
int32_t altitude_rel;
|
2016-01-28 18:51:52 -04:00
|
|
|
int32_t altitude_gps;
|
2016-01-06 20:29:52 -04:00
|
|
|
int16_t roll;
|
|
|
|
int16_t pitch;
|
|
|
|
uint16_t yaw;
|
|
|
|
};
|
|
|
|
|
2015-11-05 19:50:54 -04:00
|
|
|
struct PACKED log_Attitude {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
int16_t control_roll;
|
|
|
|
int16_t roll;
|
|
|
|
int16_t control_pitch;
|
|
|
|
int16_t pitch;
|
|
|
|
uint16_t control_yaw;
|
|
|
|
uint16_t yaw;
|
|
|
|
uint16_t error_rp;
|
|
|
|
uint16_t error_yaw;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_PID {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
2019-06-27 06:31:52 -03:00
|
|
|
float target;
|
2018-08-08 01:11:43 -03:00
|
|
|
float actual;
|
2019-06-27 06:31:52 -03:00
|
|
|
float error;
|
2015-11-05 19:50:54 -04:00
|
|
|
float P;
|
|
|
|
float I;
|
|
|
|
float D;
|
|
|
|
float FF;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_Current {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
2017-05-30 22:44:40 -03:00
|
|
|
float voltage;
|
|
|
|
float voltage_resting;
|
2016-06-02 18:00:57 -03:00
|
|
|
float current_amps;
|
2015-11-05 19:50:54 -04:00
|
|
|
float current_total;
|
2017-12-05 05:54:11 -04:00
|
|
|
float consumed_wh;
|
2017-04-08 16:04:12 -03:00
|
|
|
int16_t temperature; // degrees C * 100
|
2017-05-30 22:44:40 -03:00
|
|
|
float resistance;
|
|
|
|
};
|
|
|
|
|
2019-02-05 01:00:28 -04:00
|
|
|
struct PACKED log_WheelEncoder {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
float distance_0;
|
|
|
|
uint8_t quality_0;
|
|
|
|
float distance_1;
|
|
|
|
uint8_t quality_1;
|
|
|
|
};
|
|
|
|
|
2019-02-23 15:31:20 -04:00
|
|
|
struct PACKED log_ADSB {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint32_t ICAO_address;
|
|
|
|
int32_t lat;
|
|
|
|
int32_t lng;
|
|
|
|
int32_t alt;
|
|
|
|
uint16_t heading;
|
|
|
|
uint16_t hor_velocity;
|
|
|
|
int16_t ver_velocity;
|
|
|
|
uint16_t squawk;
|
|
|
|
};
|
|
|
|
|
2017-05-30 22:44:40 -03:00
|
|
|
struct PACKED log_Current_Cells {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
float voltage;
|
2017-04-08 16:04:12 -03:00
|
|
|
uint16_t cell_voltages[10];
|
2015-11-05 19:50:54 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_Compass {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
int16_t mag_x;
|
|
|
|
int16_t mag_y;
|
|
|
|
int16_t mag_z;
|
|
|
|
int16_t offset_x;
|
|
|
|
int16_t offset_y;
|
|
|
|
int16_t offset_z;
|
|
|
|
int16_t motor_offset_x;
|
|
|
|
int16_t motor_offset_y;
|
|
|
|
int16_t motor_offset_z;
|
|
|
|
uint8_t health;
|
2016-05-04 04:10:25 -03:00
|
|
|
uint32_t SUS;
|
2015-11-05 19:50:54 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_Mode {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t mode;
|
|
|
|
uint8_t mode_num;
|
2016-01-25 19:45:27 -04:00
|
|
|
uint8_t mode_reason;
|
2015-11-05 19:50:54 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
/*
|
|
|
|
rangefinder - support for 4 sensors
|
|
|
|
*/
|
|
|
|
struct PACKED log_RFND {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
2019-05-29 21:28:17 -03:00
|
|
|
uint8_t instance;
|
|
|
|
uint16_t dist;
|
|
|
|
uint8_t status;
|
|
|
|
uint8_t orient;
|
2015-11-05 19:50:54 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
/*
|
|
|
|
terrain log structure
|
|
|
|
*/
|
|
|
|
struct PACKED log_TERRAIN {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t status;
|
|
|
|
int32_t lat;
|
|
|
|
int32_t lng;
|
|
|
|
uint16_t spacing;
|
|
|
|
float terrain_height;
|
|
|
|
float current_height;
|
|
|
|
uint16_t pending;
|
|
|
|
uint16_t loaded;
|
|
|
|
};
|
|
|
|
|
|
|
|
/*
|
|
|
|
UBlox logging
|
|
|
|
*/
|
|
|
|
struct PACKED log_Ubx1 {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t instance;
|
|
|
|
uint16_t noisePerMS;
|
|
|
|
uint8_t jamInd;
|
|
|
|
uint8_t aPower;
|
|
|
|
uint16_t agcCnt;
|
2017-10-04 15:08:21 -03:00
|
|
|
uint32_t config;
|
2015-11-05 19:50:54 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_Ubx2 {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t instance;
|
|
|
|
int8_t ofsI;
|
|
|
|
uint8_t magI;
|
|
|
|
int8_t ofsQ;
|
|
|
|
uint8_t magQ;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_GPS_RAW {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
int32_t iTOW;
|
|
|
|
int16_t week;
|
|
|
|
uint8_t numSV;
|
|
|
|
uint8_t sv;
|
|
|
|
double cpMes;
|
|
|
|
double prMes;
|
|
|
|
float doMes;
|
|
|
|
int8_t mesQI;
|
|
|
|
int8_t cno;
|
|
|
|
uint8_t lli;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_GPS_RAWH {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
double rcvTow;
|
|
|
|
uint16_t week;
|
|
|
|
int8_t leapS;
|
|
|
|
uint8_t numMeas;
|
|
|
|
uint8_t recStat;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_GPS_RAWS {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
double prMes;
|
|
|
|
double cpMes;
|
|
|
|
float doMes;
|
|
|
|
uint8_t gnssId;
|
|
|
|
uint8_t svId;
|
|
|
|
uint8_t freqId;
|
|
|
|
uint16_t locktime;
|
|
|
|
uint8_t cno;
|
|
|
|
uint8_t prStdev;
|
|
|
|
uint8_t cpStdev;
|
|
|
|
uint8_t doStdev;
|
|
|
|
uint8_t trkStat;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_GPS_SBF_EVENT {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint32_t TOW;
|
|
|
|
uint16_t WNc;
|
|
|
|
uint8_t Mode;
|
|
|
|
uint8_t Error;
|
|
|
|
double Latitude;
|
|
|
|
double Longitude;
|
|
|
|
double Height;
|
|
|
|
float Undulation;
|
|
|
|
float Vn;
|
|
|
|
float Ve;
|
|
|
|
float Vu;
|
|
|
|
float COG;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_Esc {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
2018-04-02 01:21:56 -03:00
|
|
|
int32_t rpm;
|
|
|
|
uint16_t voltage;
|
|
|
|
uint16_t current;
|
2015-11-05 19:50:54 -04:00
|
|
|
int16_t temperature;
|
2018-04-02 01:21:56 -03:00
|
|
|
uint16_t current_tot;
|
2015-11-05 19:50:54 -04:00
|
|
|
};
|
|
|
|
|
2020-01-07 17:36:42 -04:00
|
|
|
struct PACKED log_CSRV {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t id;
|
|
|
|
float position;
|
|
|
|
float force;
|
|
|
|
float speed;
|
|
|
|
uint8_t power_pct;
|
|
|
|
};
|
|
|
|
|
2020-01-04 00:56:44 -04:00
|
|
|
struct PACKED log_CESC {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t id;
|
|
|
|
uint32_t error_count;
|
|
|
|
float voltage;
|
|
|
|
float current;
|
|
|
|
float temperature;
|
|
|
|
int32_t rpm;
|
|
|
|
uint8_t power_pct;
|
|
|
|
};
|
|
|
|
|
2015-11-05 19:50:54 -04:00
|
|
|
struct PACKED log_AIRSPEED {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
float airspeed;
|
|
|
|
float diffpressure;
|
|
|
|
int16_t temperature;
|
|
|
|
float rawpressure;
|
|
|
|
float offset;
|
2016-05-12 18:50:57 -03:00
|
|
|
bool use;
|
2017-11-03 07:28:20 -03:00
|
|
|
bool healthy;
|
2019-02-03 11:06:55 -04:00
|
|
|
float health_prob;
|
2017-11-03 07:28:20 -03:00
|
|
|
uint8_t primary;
|
2015-11-05 19:50:54 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_ACCEL {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint64_t sample_us;
|
|
|
|
float AccX, AccY, AccZ;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_GYRO {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint64_t sample_us;
|
|
|
|
float GyrX, GyrY, GyrZ;
|
|
|
|
};
|
|
|
|
|
2019-02-11 04:38:01 -04:00
|
|
|
struct PACKED log_MAV_Stats {
|
2015-11-10 02:34:31 -04:00
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint32_t timestamp;
|
|
|
|
uint32_t seqno;
|
|
|
|
uint32_t dropped;
|
|
|
|
uint32_t retries;
|
|
|
|
uint32_t resends;
|
|
|
|
uint8_t state_free_avg;
|
|
|
|
uint8_t state_free_min;
|
|
|
|
uint8_t state_free_max;
|
|
|
|
uint8_t state_pending_avg;
|
|
|
|
uint8_t state_pending_min;
|
|
|
|
uint8_t state_pending_max;
|
|
|
|
uint8_t state_sent_avg;
|
|
|
|
uint8_t state_sent_min;
|
|
|
|
uint8_t state_sent_max;
|
|
|
|
// uint8_t state_retry_avg;
|
|
|
|
// uint8_t state_retry_min;
|
|
|
|
// uint8_t state_retry_max;
|
|
|
|
};
|
|
|
|
|
2015-11-05 19:50:54 -04:00
|
|
|
struct PACKED log_ORGN {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t origin_type;
|
|
|
|
int32_t latitude;
|
|
|
|
int32_t longitude;
|
|
|
|
int32_t altitude;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_RPM {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
float rpm1;
|
|
|
|
float rpm2;
|
|
|
|
};
|
|
|
|
|
2016-03-24 22:11:11 -03:00
|
|
|
struct PACKED log_Rate {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
float control_roll;
|
|
|
|
float roll;
|
|
|
|
float roll_out;
|
|
|
|
float control_pitch;
|
|
|
|
float pitch;
|
|
|
|
float pitch_out;
|
|
|
|
float control_yaw;
|
|
|
|
float yaw;
|
|
|
|
float yaw_out;
|
|
|
|
float control_accel;
|
|
|
|
float accel;
|
|
|
|
float accel_out;
|
|
|
|
};
|
|
|
|
|
2015-11-09 18:10:46 -04:00
|
|
|
struct PACKED log_SbpLLH {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint32_t tow;
|
|
|
|
int32_t lat;
|
|
|
|
int32_t lon;
|
|
|
|
int32_t alt;
|
|
|
|
uint8_t n_sats;
|
|
|
|
uint8_t flags;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_SbpHealth {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint32_t crc_error_counter;
|
|
|
|
uint32_t last_injected_data_ms;
|
|
|
|
uint32_t last_iar_num_hypotheses;
|
|
|
|
};
|
|
|
|
|
2017-06-26 12:41:24 -03:00
|
|
|
struct PACKED log_SbpRAWH {
|
2015-11-09 18:10:46 -04:00
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint16_t msg_type;
|
|
|
|
uint16_t sender_id;
|
2017-06-26 12:41:24 -03:00
|
|
|
uint8_t index;
|
|
|
|
uint8_t pages;
|
2015-11-09 18:10:46 -04:00
|
|
|
uint8_t msg_len;
|
2017-06-26 12:41:24 -03:00
|
|
|
uint8_t res;
|
|
|
|
uint8_t data[48];
|
2015-11-09 18:10:46 -04:00
|
|
|
};
|
|
|
|
|
2017-06-26 12:41:24 -03:00
|
|
|
struct PACKED log_SbpRAWM {
|
2015-11-09 18:10:46 -04:00
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint16_t msg_type;
|
2017-06-26 12:41:24 -03:00
|
|
|
uint16_t sender_id;
|
|
|
|
uint8_t index;
|
|
|
|
uint8_t pages;
|
|
|
|
uint8_t msg_len;
|
|
|
|
uint8_t res;
|
|
|
|
uint8_t data[104];
|
2015-11-09 18:10:46 -04:00
|
|
|
};
|
|
|
|
|
2017-06-29 11:17:10 -03:00
|
|
|
struct PACKED log_SbpEvent {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint16_t wn;
|
|
|
|
uint32_t tow;
|
|
|
|
int32_t ns_residual;
|
|
|
|
uint8_t level;
|
|
|
|
uint8_t quality;
|
|
|
|
};
|
|
|
|
|
2016-07-03 23:14:26 -03:00
|
|
|
struct PACKED log_Rally {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t total;
|
|
|
|
uint8_t sequence;
|
|
|
|
int32_t latitude;
|
|
|
|
int32_t longitude;
|
|
|
|
int16_t altitude;
|
|
|
|
};
|
|
|
|
|
2017-04-09 08:17:17 -03:00
|
|
|
struct PACKED log_AOA_SSA {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
float AOA;
|
|
|
|
float SSA;
|
|
|
|
};
|
|
|
|
|
2017-04-18 11:43:03 -03:00
|
|
|
struct PACKED log_Beacon {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t health;
|
|
|
|
uint8_t count;
|
|
|
|
float dist0;
|
|
|
|
float dist1;
|
|
|
|
float dist2;
|
|
|
|
float dist3;
|
|
|
|
float posx;
|
|
|
|
float posy;
|
|
|
|
float posz;
|
|
|
|
};
|
|
|
|
|
2017-07-14 14:00:13 -03:00
|
|
|
// proximity sensor logging
|
|
|
|
struct PACKED log_Proximity {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t health;
|
|
|
|
float dist0;
|
|
|
|
float dist45;
|
|
|
|
float dist90;
|
|
|
|
float dist135;
|
|
|
|
float dist180;
|
|
|
|
float dist225;
|
|
|
|
float dist270;
|
|
|
|
float dist315;
|
|
|
|
float distup;
|
|
|
|
float closest_angle;
|
|
|
|
float closest_dist;
|
|
|
|
};
|
|
|
|
|
2017-11-15 23:20:17 -04:00
|
|
|
struct PACKED log_Performance {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint16_t num_long_running;
|
|
|
|
uint16_t num_loops;
|
|
|
|
uint32_t max_time;
|
|
|
|
uint32_t mem_avail;
|
2018-02-15 11:58:48 -04:00
|
|
|
uint16_t load;
|
2018-08-07 07:00:10 -03:00
|
|
|
uint32_t internal_errors;
|
2019-06-03 01:17:02 -03:00
|
|
|
uint32_t internal_error_count;
|
2019-05-16 04:57:54 -03:00
|
|
|
uint32_t spi_count;
|
|
|
|
uint32_t i2c_count;
|
2019-08-25 04:47:09 -03:00
|
|
|
uint32_t i2c_isr_count;
|
2019-09-17 05:13:44 -03:00
|
|
|
uint32_t extra_loop_us;
|
2017-11-15 23:20:17 -04:00
|
|
|
};
|
|
|
|
|
2017-07-26 14:09:33 -03:00
|
|
|
struct PACKED log_SRTL {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t active;
|
|
|
|
uint16_t num_points;
|
|
|
|
uint16_t max_points;
|
|
|
|
uint8_t action;
|
|
|
|
float N;
|
|
|
|
float E;
|
|
|
|
float D;
|
|
|
|
};
|
|
|
|
|
2019-08-05 03:22:05 -03:00
|
|
|
struct PACKED log_OABendyRuler {
|
2019-06-08 01:59:04 -03:00
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
2019-08-05 03:22:05 -03:00
|
|
|
uint8_t active;
|
|
|
|
uint16_t target_yaw;
|
|
|
|
uint16_t yaw;
|
|
|
|
float margin;
|
|
|
|
int32_t final_lat;
|
|
|
|
int32_t final_lng;
|
|
|
|
int32_t oa_lat;
|
|
|
|
int32_t oa_lng;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED log_OADijkstra {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t state;
|
2019-09-07 01:56:51 -03:00
|
|
|
uint8_t error_id;
|
2019-08-05 03:22:05 -03:00
|
|
|
uint8_t curr_point;
|
|
|
|
uint8_t tot_points;
|
2019-06-08 01:59:04 -03:00
|
|
|
int32_t final_lat;
|
|
|
|
int32_t final_lng;
|
|
|
|
int32_t oa_lat;
|
|
|
|
int32_t oa_lng;
|
|
|
|
};
|
|
|
|
|
2017-10-12 19:26:43 -03:00
|
|
|
struct PACKED log_DSTL {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t stage;
|
|
|
|
float target_heading;
|
|
|
|
int32_t target_lat;
|
|
|
|
int32_t target_lng;
|
|
|
|
int32_t target_alt;
|
|
|
|
int16_t crosstrack_error;
|
|
|
|
int16_t travel_distance;
|
|
|
|
float l1_i;
|
|
|
|
int32_t loiter_sum_cd;
|
|
|
|
float desired;
|
|
|
|
float P;
|
|
|
|
float I;
|
|
|
|
float D;
|
|
|
|
};
|
|
|
|
|
2019-05-03 08:25:08 -03:00
|
|
|
struct PACKED log_Arm_Disarm {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t arm_state;
|
|
|
|
uint16_t arm_checks;
|
|
|
|
};
|
2015-11-09 18:10:46 -04:00
|
|
|
|
2015-12-07 20:51:46 -04:00
|
|
|
// FMT messages define all message formats other than FMT
|
|
|
|
// UNIT messages define units which can be referenced by FMTU messages
|
|
|
|
// FMTU messages associate types (e.g. centimeters/second/second) to FMT message fields
|
|
|
|
|
2017-04-05 03:37:34 -03:00
|
|
|
#define ACC_LABELS "TimeUS,SampleUS,AccX,AccY,AccZ"
|
2015-12-07 20:51:46 -04:00
|
|
|
#define ACC_FMT "QQfff"
|
|
|
|
#define ACC_UNITS "ssnnn"
|
|
|
|
#define ACC_MULTS "FF000"
|
2017-04-05 03:37:34 -03:00
|
|
|
|
2019-01-18 00:24:08 -04:00
|
|
|
// see "struct sensor" in AP_Baro.h and "Write_Baro":
|
2019-07-30 21:07:34 -03:00
|
|
|
#define BARO_LABELS "TimeUS,Alt,Press,Temp,CRt,SMS,Offset,GndTemp,Health"
|
|
|
|
#define BARO_FMT "QffcfIffB"
|
|
|
|
#define BARO_UNITS "smPOnsmO-"
|
|
|
|
#define BARO_MULTS "F00B0C?0-"
|
2017-04-05 03:37:34 -03:00
|
|
|
|
2018-04-02 01:21:56 -03:00
|
|
|
#define ESC_LABELS "TimeUS,RPM,Volt,Curr,Temp,CTot"
|
|
|
|
#define ESC_FMT "QeCCcH"
|
|
|
|
#define ESC_UNITS "sqvAO-"
|
|
|
|
#define ESC_MULTS "FBBBB-"
|
2017-04-05 03:37:34 -03:00
|
|
|
|
2019-09-03 16:40:48 -03:00
|
|
|
#define GPA_LABELS "TimeUS,VDop,HAcc,VAcc,SAcc,YAcc,VV,SMS,Delta"
|
|
|
|
#define GPA_FMT "QCCCCfBIH"
|
|
|
|
#define GPA_UNITS "smmmnd-ss"
|
|
|
|
#define GPA_MULTS "FBBBB0-CC"
|
2017-04-05 03:37:34 -03:00
|
|
|
|
2019-01-18 00:24:08 -04:00
|
|
|
// see "struct GPS_State" and "Write_GPS":
|
2017-05-28 04:12:50 -03:00
|
|
|
#define GPS_LABELS "TimeUS,Status,GMS,GWk,NSats,HDop,Lat,Lng,Alt,Spd,GCrs,VZ,Yaw,U"
|
|
|
|
#define GPS_FMT "QBIHBcLLeffffB"
|
|
|
|
#define GPS_UNITS "s---SmDUmnhnh-"
|
|
|
|
#define GPS_MULTS "F---0BGGB000--"
|
2017-04-05 03:37:34 -03:00
|
|
|
|
|
|
|
#define GYR_LABELS "TimeUS,SampleUS,GyrX,GyrY,GyrZ"
|
|
|
|
#define GYR_FMT "QQfff"
|
2015-12-07 20:51:46 -04:00
|
|
|
#define GYR_UNITS "ssEEE"
|
|
|
|
#define GYR_MULTS "FF000"
|
2017-04-05 03:37:34 -03:00
|
|
|
|
|
|
|
#define IMT_LABELS "TimeUS,DelT,DelvT,DelaT,DelAX,DelAY,DelAZ,DelVX,DelVY,DelVZ"
|
|
|
|
#define IMT_FMT "Qfffffffff"
|
2015-12-07 20:51:46 -04:00
|
|
|
#define IMT_UNITS "ssssrrrnnn"
|
|
|
|
#define IMT_MULTS "FF00000000"
|
2017-04-05 03:37:34 -03:00
|
|
|
|
2017-10-10 20:36:04 -03:00
|
|
|
#define ISBH_LABELS "TimeUS,N,type,instance,mul,smp_cnt,SampleUS,smp_rate"
|
|
|
|
#define ISBH_FMT "QHBBHHQf"
|
2015-12-07 20:51:46 -04:00
|
|
|
#define ISBH_UNITS "s-----sz"
|
|
|
|
#define ISBH_MULTS "F-----F-"
|
2017-09-01 08:05:16 -03:00
|
|
|
|
|
|
|
#define ISBD_LABELS "TimeUS,N,seqno,x,y,z"
|
|
|
|
#define ISBD_FMT "QHHaaa"
|
2015-12-07 20:51:46 -04:00
|
|
|
#define ISBD_UNITS "s--ooo"
|
|
|
|
#define ISBD_MULTS "F--???"
|
2017-09-01 08:05:16 -03:00
|
|
|
|
2017-05-01 00:00:46 -03:00
|
|
|
#define IMU_LABELS "TimeUS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,EG,EA,T,GH,AH,GHz,AHz"
|
|
|
|
#define IMU_FMT "QffffffIIfBBHH"
|
2015-12-07 20:51:46 -04:00
|
|
|
#define IMU_UNITS "sEEEooo--O--zz"
|
|
|
|
#define IMU_MULTS "F000000-----00"
|
2017-04-05 03:37:34 -03:00
|
|
|
|
|
|
|
#define MAG_LABELS "TimeUS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ,Health,S"
|
|
|
|
#define MAG_FMT "QhhhhhhhhhBI"
|
2015-12-07 20:51:46 -04:00
|
|
|
#define MAG_UNITS "sGGGGGGGGG-s"
|
|
|
|
#define MAG_MULTS "FCCCCCCCCC-F"
|
2017-04-05 03:37:34 -03:00
|
|
|
|
2019-07-25 12:13:34 -03:00
|
|
|
#define PID_LABELS "TimeUS,Tar,Act,Err,P,I,D,FF"
|
2019-06-27 06:31:52 -03:00
|
|
|
#define PID_FMT "Qfffffff"
|
|
|
|
#define PID_UNITS "s-------"
|
|
|
|
#define PID_MULTS "F-------"
|
2017-04-05 03:37:34 -03:00
|
|
|
|
2017-04-15 07:37:00 -03:00
|
|
|
#define QUAT_LABELS "TimeUS,Q1,Q2,Q3,Q4"
|
|
|
|
#define QUAT_FMT "Qffff"
|
2015-12-07 20:51:46 -04:00
|
|
|
#define QUAT_UNITS "s????"
|
|
|
|
#define QUAT_MULTS "F????"
|
2017-04-15 07:37:00 -03:00
|
|
|
|
2017-12-05 05:54:11 -04:00
|
|
|
#define CURR_LABELS "TimeUS,Volt,VoltR,Curr,CurrTot,EnrgTot,Temp,Res"
|
|
|
|
#define CURR_FMT "Qfffffcf"
|
2018-05-04 06:39:09 -03:00
|
|
|
#define CURR_UNITS "svvA?JOw"
|
|
|
|
#define CURR_MULTS "F000?/?0"
|
2017-05-30 22:44:40 -03:00
|
|
|
|
|
|
|
#define CURR_CELL_LABELS "TimeUS,Volt,V1,V2,V3,V4,V5,V6,V7,V8,V9,V10"
|
|
|
|
#define CURR_CELL_FMT "QfHHHHHHHHHH"
|
2015-12-07 20:51:46 -04:00
|
|
|
#define CURR_CELL_UNITS "svvvvvvvvvvv"
|
|
|
|
#define CURR_CELL_MULTS "F00000000000"
|
2017-04-05 03:37:34 -03:00
|
|
|
|
2019-02-03 11:06:55 -04:00
|
|
|
#define ARSP_LABELS "TimeUS,Airspeed,DiffPress,Temp,RawPress,Offset,U,Health,Hfp,Pri"
|
|
|
|
#define ARSP_FMT "QffcffBBfB"
|
|
|
|
#define ARSP_UNITS "snPOPP----"
|
|
|
|
#define ARSP_MULTS "F00B00----"
|
2017-11-03 07:28:20 -03:00
|
|
|
|
2015-11-05 19:50:54 -04:00
|
|
|
// messages for all boards
|
|
|
|
#define LOG_BASE_STRUCTURES \
|
|
|
|
{ LOG_FORMAT_MSG, sizeof(log_Format), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"FMT", "BBnNZ", "Type,Length,Name,Format,Columns", "-b---", "-----" }, \
|
|
|
|
{ LOG_UNIT_MSG, sizeof(log_Unit), \
|
|
|
|
"UNIT", "QbZ", "TimeUS,Id,Label", "s--","F--" }, \
|
|
|
|
{ LOG_FORMAT_UNITS_MSG, sizeof(log_Format_Units), \
|
|
|
|
"FMTU", "QBNN", "TimeUS,FmtType,UnitIds,MultIds","s---", "F---" }, \
|
|
|
|
{ LOG_MULT_MSG, sizeof(log_Format_Multiplier), \
|
|
|
|
"MULT", "Qbd", "TimeUS,Id,Mult", "s--","F--" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_PARAMETER_MSG, sizeof(log_Parameter), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"PARM", "QNf", "TimeUS,Name,Value", "s--", "F--" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_GPS_MSG, sizeof(log_GPS), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"GPS", GPS_FMT, GPS_LABELS, GPS_UNITS, GPS_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_GPS2_MSG, sizeof(log_GPS), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"GPS2", GPS_FMT, GPS_LABELS, GPS_UNITS, GPS_MULTS }, \
|
2017-03-10 02:48:51 -04:00
|
|
|
{ LOG_GPSB_MSG, sizeof(log_GPS), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"GPSB", GPS_FMT, GPS_LABELS, GPS_UNITS, GPS_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_GPA_MSG, sizeof(log_GPA), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"GPA", GPA_FMT, GPA_LABELS, GPA_UNITS, GPA_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_GPA2_MSG, sizeof(log_GPA), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"GPA2", GPA_FMT, GPA_LABELS, GPA_UNITS, GPA_MULTS }, \
|
2017-03-10 02:48:51 -04:00
|
|
|
{ LOG_GPAB_MSG, sizeof(log_GPA), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"GPAB", GPA_FMT, GPA_LABELS, GPA_UNITS, GPA_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_IMU_MSG, sizeof(log_IMU), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"IMU", IMU_FMT, IMU_LABELS, IMU_UNITS, IMU_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_MESSAGE_MSG, sizeof(log_Message), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"MSG", "QZ", "TimeUS,Message", "s-", "F-"}, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_RCIN_MSG, sizeof(log_RCIN), \
|
2018-10-14 01:45:42 -03:00
|
|
|
"RCIN", "QHHHHHHHHHHHHHH", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14", "sYYYYYYYYYYYYYY", "F--------------" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_RCOUT_MSG, sizeof(log_RCOUT), \
|
2018-10-14 01:45:42 -03:00
|
|
|
"RCOU", "QHHHHHHHHHHHHHH", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14", "sYYYYYYYYYYYYYY", "F--------------" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_RSSI_MSG, sizeof(log_RSSI), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"RSSI", "Qf", "TimeUS,RXRSSI", "s-", "F-" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_BARO_MSG, sizeof(log_BARO), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"BARO", BARO_FMT, BARO_LABELS, BARO_UNITS, BARO_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_POWR_MSG, sizeof(log_POWR), \
|
2018-06-14 01:46:36 -03:00
|
|
|
"POWR","QffHB","TimeUS,Vcc,VServo,Flags,Safety", "svv--", "F00--" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_CMD_MSG, sizeof(log_Cmd), \
|
2018-11-24 23:10:07 -04:00
|
|
|
"CMD", "QHHHffffLLfB","TimeUS,CTot,CNum,CId,Prm1,Prm2,Prm3,Prm4,Lat,Lng,Alt,Frame", "s-------DUm-", "F-------GG0-" }, \
|
2019-08-22 22:21:39 -03:00
|
|
|
{ LOG_MAVLINK_COMMAND_MSG, sizeof(log_MAVLink_Command), \
|
|
|
|
"MAVC", "QBBBHBBffffiifBB","TimeUS,TS,TC,Fr,Cmd,Cur,AC,P1,P2,P3,P4,X,Y,Z,Res,WL", "s---------------", "F---------------" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_RADIO_MSG, sizeof(log_Radio), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"RAD", "QBBBBBHH", "TimeUS,RSSI,RemRSSI,TxBuf,Noise,RemNoise,RxErrors,Fixed", "s-------", "F-------" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_CAMERA_MSG, sizeof(log_Camera), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"CAM", "QIHLLeeeccC","TimeUS,GPSTime,GPSWeek,Lat,Lng,Alt,RelAlt,GPSAlt,Roll,Pitch,Yaw", "s--DUmmmddd", "F--GGBBBBBB" }, \
|
2016-01-28 18:51:52 -04:00
|
|
|
{ LOG_TRIGGER_MSG, sizeof(log_Camera), \
|
2018-03-01 01:45:18 -04:00
|
|
|
"TRIG", "QIHLLeeeccC","TimeUS,GPSTime,GPSWeek,Lat,Lng,Alt,RelAlt,GPSAlt,Roll,Pitch,Yaw", "s--DUmmmddd", "F--GGBBBBBB" }, \
|
2017-11-03 07:28:20 -03:00
|
|
|
{ LOG_ARSP_MSG, sizeof(log_AIRSPEED), "ARSP", ARSP_FMT, ARSP_LABELS, ARSP_UNITS, ARSP_MULTS }, \
|
|
|
|
{ LOG_ASP2_MSG, sizeof(log_AIRSPEED), "ASP2", ARSP_FMT, ARSP_LABELS, ARSP_UNITS, ARSP_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_CURRENT_MSG, sizeof(log_Current), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"BAT", CURR_FMT,CURR_LABELS,CURR_UNITS,CURR_MULTS }, \
|
2016-06-02 18:00:57 -03:00
|
|
|
{ LOG_CURRENT2_MSG, sizeof(log_Current), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"BAT2", CURR_FMT,CURR_LABELS,CURR_UNITS,CURR_MULTS }, \
|
2018-09-12 20:39:30 -03:00
|
|
|
{ LOG_CURRENT3_MSG, sizeof(log_Current), \
|
|
|
|
"BAT3", CURR_FMT,CURR_LABELS,CURR_UNITS,CURR_MULTS }, \
|
|
|
|
{ LOG_CURRENT4_MSG, sizeof(log_Current), \
|
|
|
|
"BAT4", CURR_FMT,CURR_LABELS,CURR_UNITS,CURR_MULTS }, \
|
|
|
|
{ LOG_CURRENT5_MSG, sizeof(log_Current), \
|
|
|
|
"BAT5", CURR_FMT,CURR_LABELS,CURR_UNITS,CURR_MULTS }, \
|
|
|
|
{ LOG_CURRENT6_MSG, sizeof(log_Current), \
|
|
|
|
"BAT6", CURR_FMT,CURR_LABELS,CURR_UNITS,CURR_MULTS }, \
|
|
|
|
{ LOG_CURRENT7_MSG, sizeof(log_Current), \
|
|
|
|
"BAT7", CURR_FMT,CURR_LABELS,CURR_UNITS,CURR_MULTS }, \
|
|
|
|
{ LOG_CURRENT8_MSG, sizeof(log_Current), \
|
|
|
|
"BAT8", CURR_FMT,CURR_LABELS,CURR_UNITS,CURR_MULTS }, \
|
|
|
|
{ LOG_CURRENT9_MSG, sizeof(log_Current), \
|
|
|
|
"BAT9", CURR_FMT,CURR_LABELS,CURR_UNITS,CURR_MULTS }, \
|
2017-05-30 22:44:40 -03:00
|
|
|
{ LOG_CURRENT_CELLS_MSG, sizeof(log_Current_Cells), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"BCL", CURR_CELL_FMT, CURR_CELL_LABELS, CURR_CELL_UNITS, CURR_CELL_MULTS }, \
|
2017-05-30 22:44:40 -03:00
|
|
|
{ LOG_CURRENT_CELLS2_MSG, sizeof(log_Current_Cells), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"BCL2", CURR_CELL_FMT, CURR_CELL_LABELS, CURR_CELL_UNITS, CURR_CELL_MULTS }, \
|
2018-09-12 20:39:30 -03:00
|
|
|
{ LOG_CURRENT_CELLS3_MSG, sizeof(log_Current_Cells), \
|
|
|
|
"BCL3", CURR_CELL_FMT, CURR_CELL_LABELS, CURR_CELL_UNITS, CURR_CELL_MULTS }, \
|
|
|
|
{ LOG_CURRENT_CELLS4_MSG, sizeof(log_Current_Cells), \
|
|
|
|
"BCL4", CURR_CELL_FMT, CURR_CELL_LABELS, CURR_CELL_UNITS, CURR_CELL_MULTS }, \
|
|
|
|
{ LOG_CURRENT_CELLS5_MSG, sizeof(log_Current_Cells), \
|
|
|
|
"BCL5", CURR_CELL_FMT, CURR_CELL_LABELS, CURR_CELL_UNITS, CURR_CELL_MULTS }, \
|
|
|
|
{ LOG_CURRENT_CELLS6_MSG, sizeof(log_Current_Cells), \
|
|
|
|
"BCL6", CURR_CELL_FMT, CURR_CELL_LABELS, CURR_CELL_UNITS, CURR_CELL_MULTS }, \
|
|
|
|
{ LOG_CURRENT_CELLS7_MSG, sizeof(log_Current_Cells), \
|
|
|
|
"BCL7", CURR_CELL_FMT, CURR_CELL_LABELS, CURR_CELL_UNITS, CURR_CELL_MULTS }, \
|
|
|
|
{ LOG_CURRENT_CELLS8_MSG, sizeof(log_Current_Cells), \
|
|
|
|
"BCL8", CURR_CELL_FMT, CURR_CELL_LABELS, CURR_CELL_UNITS, CURR_CELL_MULTS }, \
|
|
|
|
{ LOG_CURRENT_CELLS9_MSG, sizeof(log_Current_Cells), \
|
|
|
|
"BCL9", CURR_CELL_FMT, CURR_CELL_LABELS, CURR_CELL_UNITS, CURR_CELL_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),\
|
2015-12-07 20:51:46 -04:00
|
|
|
"ATT", "QccccCCCC", "TimeUS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw,ErrRP,ErrYaw", "sddddhhdh", "FBBBBBBBB" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_COMPASS_MSG, sizeof(log_Compass), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"MAG", MAG_FMT, MAG_LABELS, MAG_UNITS, MAG_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_MODE_MSG, sizeof(log_Mode), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"MODE", "QMBB", "TimeUS,Mode,ModeNum,Rsn", "s---", "F---" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_RFND_MSG, sizeof(log_RFND), \
|
2019-05-29 21:28:17 -03:00
|
|
|
"RFND", "QBCBB", "TimeUS,Instance,Dist,Stat,Orient", "s#m--", "F-B--" }, \
|
2019-02-11 04:38:01 -04:00
|
|
|
{ LOG_MAV_STATS, sizeof(log_MAV_Stats), \
|
2018-08-07 07:22:21 -03:00
|
|
|
"DMS", "IIIIIBBBBBBBBB", "TimeMS,N,Dp,RT,RS,Fa,Fmn,Fmx,Pa,Pmn,Pmx,Sa,Smn,Smx", "s-------------", "C-------------" }, \
|
2017-04-18 11:43:03 -03:00
|
|
|
{ LOG_BEACON_MSG, sizeof(log_Beacon), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"BCN", "QBBfffffff", "TimeUS,Health,Cnt,D0,D1,D2,D3,PosX,PosY,PosZ", "s--mmmmmmm", "F--BBBBBBB" }, \
|
2017-07-14 14:00:13 -03:00
|
|
|
{ LOG_PROXIMITY_MSG, sizeof(log_Proximity), \
|
2019-07-27 00:10:49 -03:00
|
|
|
"PRX", "QBfffffffffff", "TimeUS,Health,D0,D45,D90,D135,D180,D225,D270,D315,DUp,CAn,CDis", "s-mmmmmmmmmhm", "F-00000000000" }, \
|
2017-11-15 23:20:17 -04:00
|
|
|
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance), \
|
2019-09-17 05:13:44 -03:00
|
|
|
"PM", "QHHIIHIIIIII", "TimeUS,NLon,NLoop,MaxT,Mem,Load,IntE,IntEC,SPIC,I2CC,I2CI,ExUS", "s---b%-----s", "F---0A-----F" }, \
|
2017-07-26 14:09:33 -03:00
|
|
|
{ LOG_SRTL_MSG, sizeof(log_SRTL), \
|
2019-06-08 01:59:04 -03:00
|
|
|
"SRTL", "QBHHBfff", "TimeUS,Active,NumPts,MaxPts,Action,N,E,D", "s----mmm", "F----000" }, \
|
2019-08-05 03:22:05 -03:00
|
|
|
{ LOG_OA_BENDYRULER_MSG, sizeof(log_OABendyRuler), \
|
|
|
|
"OABR","QBHHfLLLL","TimeUS,Active,DesYaw,Yaw,Mar,DLat,DLng,OALat,OALng", "sbddmDUDU", "F----GGGG" }, \
|
|
|
|
{ LOG_OA_DIJKSTRA_MSG, sizeof(log_OADijkstra), \
|
2019-09-07 01:56:51 -03:00
|
|
|
"OADJ","QBBBBLLLL","TimeUS,State,Err,CurrPoint,TotPoints,DLat,DLng,OALat,OALng", "sbbbbDUDU", "F----GGGG" }
|
2015-11-05 19:50:54 -04:00
|
|
|
|
|
|
|
// messages for more advanced boards
|
|
|
|
#define LOG_EXTRA_STRUCTURES \
|
|
|
|
{ LOG_IMU2_MSG, sizeof(log_IMU), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"IMU2", IMU_FMT, IMU_LABELS, IMU_UNITS, IMU_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_IMU3_MSG, sizeof(log_IMU), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"IMU3", IMU_FMT, IMU_LABELS, IMU_UNITS, IMU_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_AHR2_MSG, sizeof(log_AHRS), \
|
2018-05-04 06:40:00 -03:00
|
|
|
"AHR2","QccCfLLffff","TimeUS,Roll,Pitch,Yaw,Alt,Lat,Lng,Q1,Q2,Q3,Q4","sddhmDU????", "FBBB0GG????" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_POS_MSG, sizeof(log_POS), \
|
2018-05-04 06:11:55 -03:00
|
|
|
"POS","QLLfff","TimeUS,Lat,Lng,Alt,RelHomeAlt,RelOriginAlt", "sDUmmm", "FGG000" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_SIMSTATE_MSG, sizeof(log_AHRS), \
|
2018-03-01 01:45:18 -04:00
|
|
|
"SIM","QccCfLLffff","TimeUS,Roll,Pitch,Yaw,Alt,Lat,Lng,Q1,Q2,Q3,Q4", "sddhmDU????", "FBBB0GG????" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_NKF1_MSG, sizeof(log_EKF1), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"NKF1","QccCfffffffccce","TimeUS,Roll,Pitch,Yaw,VN,VE,VD,dPD,PN,PE,PD,GX,GY,GZ,OH", "sddhnnnnmmmkkkm", "FBBB0000000BBBB" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_NKF2_MSG, sizeof(log_NKF2), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"NKF2","QbccccchhhhhhB","TimeUS,AZbias,GSX,GSY,GSZ,VWN,VWE,MN,ME,MD,MX,MY,MZ,MI", "s----nnGGGGGG-", "F----BBCCCCCC-" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_NKF3_MSG, sizeof(log_NKF3), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"NKF3","Qcccccchhhcc","TimeUS,IVN,IVE,IVD,IPN,IPE,IPD,IMX,IMY,IMZ,IYAW,IVT", "snnnmmmGGG??", "FBBBBBBCCCBB" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_NKF4_MSG, sizeof(log_NKF4), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"NKF4","QcccccfbbHBHHb","TimeUS,SV,SP,SH,SM,SVT,errRP,OFN,OFE,FS,TS,SS,GPS,PI", "s------??-----", "F------??-----" }, \
|
2016-07-03 19:11:03 -03:00
|
|
|
{ LOG_NKF5_MSG, sizeof(log_NKF5), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"NKF5","QBhhhcccCCfff","TimeUS,NI,FIX,FIY,AFI,HAGL,offset,RI,rng,Herr,eAng,eVel,ePos", "s----m???mrnm", "F----BBBBB000" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_NKF6_MSG, sizeof(log_EKF1), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"NKF6","QccCfffffffccce","TimeUS,Roll,Pitch,Yaw,VN,VE,VD,dPD,PN,PE,PD,GX,GY,GZ,OH", "sddhnnn-mmmkkkm", "FBBB000-000BBBB" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_NKF7_MSG, sizeof(log_NKF2), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"NKF7","QbccccchhhhhhB","TimeUS,AZbias,GSX,GSY,GSZ,VWN,VWE,MN,ME,MD,MX,MY,MZ,MI", "s----nnGGGGGG-", "F----BBCCCCCC-" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_NKF8_MSG, sizeof(log_NKF3), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"NKF8","Qcccccchhhcc","TimeUS,IVN,IVE,IVD,IPN,IPE,IPD,IMX,IMY,IMZ,IYAW,IVT", "snnnmmmGGGd?", "FBBBBBBCCCBB" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_NKF9_MSG, sizeof(log_NKF4), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"NKF9","QcccccfbbHBHHb","TimeUS,SV,SP,SH,SM,SVT,errRP,OFN,OFE,FS,TS,SS,GPS,PI", "s-----???-----", "F-----???-----" }, \
|
2016-11-23 08:04:51 -04:00
|
|
|
{ LOG_NKF10_MSG, sizeof(log_RngBcnDebug), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"NKF0","QBccCCcccccccc","TimeUS,ID,rng,innov,SIV,TR,BPN,BPE,BPD,OFH,OFL,OFN,OFE,OFD", "s-m---mmmmmmmm", "F-B---BBBBBBBB" }, \
|
2019-07-20 03:37:11 -03:00
|
|
|
{ LOG_NKF11_MSG, sizeof(log_EKF1), \
|
|
|
|
"NK11","QccCfffffffccce","TimeUS,Roll,Pitch,Yaw,VN,VE,VD,dPD,PN,PE,PD,GX,GY,GZ,OH", "sddhnnn-mmmkkkm", "FBBB000-000BBBB" }, \
|
|
|
|
{ LOG_NKF12_MSG, sizeof(log_NKF2), \
|
|
|
|
"NK12","QbccccchhhhhhB","TimeUS,AZbias,GSX,GSY,GSZ,VWN,VWE,MN,ME,MD,MX,MY,MZ,MI", "s----nnGGGGGG-", "F----BBCCCCCC-" }, \
|
|
|
|
{ LOG_NKF13_MSG, sizeof(log_NKF3), \
|
|
|
|
"NK13","Qcccccchhhcc","TimeUS,IVN,IVE,IVD,IPN,IPE,IPD,IMX,IMY,IMZ,IYAW,IVT", "snnnmmmGGGd?", "FBBBBBBCCCBB" }, \
|
|
|
|
{ LOG_NKF14_MSG, sizeof(log_NKF4), \
|
|
|
|
"NK14","QcccccfbbHBHHb","TimeUS,SV,SP,SH,SM,SVT,errRP,OFN,OFE,FS,TS,SS,GPS,PI", "s-----???-----", "F-----???-----" }, \
|
2015-12-07 20:51:46 -04:00
|
|
|
{ LOG_NKQ1_MSG, sizeof(log_Quaternion), "NKQ1", QUAT_FMT, QUAT_LABELS, QUAT_UNITS, QUAT_MULTS }, \
|
|
|
|
{ LOG_NKQ2_MSG, sizeof(log_Quaternion), "NKQ2", QUAT_FMT, QUAT_LABELS, QUAT_UNITS, QUAT_MULTS }, \
|
2019-07-20 03:37:11 -03:00
|
|
|
{ LOG_NKQ3_MSG, sizeof(log_Quaternion), "NKQ3", QUAT_FMT, QUAT_LABELS, QUAT_UNITS, QUAT_MULTS }, \
|
2016-07-14 02:08:43 -03:00
|
|
|
{ LOG_XKF1_MSG, sizeof(log_EKF1), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"XKF1","QccCfffffffccce","TimeUS,Roll,Pitch,Yaw,VN,VE,VD,dPD,PN,PE,PD,GX,GY,GZ,OH", "sddhnnnnmmmkkkm", "FBBB0000000BBBB" }, \
|
2016-07-14 02:08:43 -03:00
|
|
|
{ LOG_XKF2_MSG, sizeof(log_NKF2a), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"XKF2","QccccchhhhhhB","TimeUS,AX,AY,AZ,VWN,VWE,MN,ME,MD,MX,MY,MZ,MI", "s---nnGGGGGG-", "F---BBCCCCCC-" }, \
|
2016-07-14 02:08:43 -03:00
|
|
|
{ LOG_XKF3_MSG, sizeof(log_NKF3), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"XKF3","Qcccccchhhcc","TimeUS,IVN,IVE,IVD,IPN,IPE,IPD,IMX,IMY,IMZ,IYAW,IVT", "snnnmmmGGG??", "FBBBBBBCCCBB" }, \
|
2016-07-14 02:08:43 -03:00
|
|
|
{ LOG_XKF4_MSG, sizeof(log_NKF4), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"XKF4","QcccccfbbHBHHb","TimeUS,SV,SP,SH,SM,SVT,errRP,OFN,OFE,FS,TS,SS,GPS,PI", "s------??-----", "F------??-----" }, \
|
2016-07-14 02:08:43 -03:00
|
|
|
{ LOG_XKF5_MSG, sizeof(log_NKF5), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"XKF5","QBhhhcccCCfff","TimeUS,NI,FIX,FIY,AFI,HAGL,offset,RI,rng,Herr,eAng,eVel,ePos", "s----m???mrnm", "F----BBBBB000" }, \
|
2016-07-14 02:08:43 -03:00
|
|
|
{ LOG_XKF6_MSG, sizeof(log_EKF1), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"XKF6","QccCfffffffccce","TimeUS,Roll,Pitch,Yaw,VN,VE,VD,dPD,PN,PE,PD,GX,GY,GZ,OH", "sddhnnn-mmmkkkm", "FBBB000-000BBBB" }, \
|
2016-07-14 02:08:43 -03:00
|
|
|
{ LOG_XKF7_MSG, sizeof(log_NKF2a), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"XKF7","QccccchhhhhhB","TimeUS,AX,AY,AZ,VWN,VWE,MN,ME,MD,MX,MY,MZ,MI", "s---nnGGGGGG-", "F---BBCCCCCC-" }, \
|
2016-07-14 02:08:43 -03:00
|
|
|
{ LOG_XKF8_MSG, sizeof(log_NKF3), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"XKF8","Qcccccchhhcc","TimeUS,IVN,IVE,IVD,IPN,IPE,IPD,IMX,IMY,IMZ,IYAW,IVT", "snnnmmmGGGd?", "FBBBBBBCCCBB" }, \
|
2016-07-14 02:08:43 -03:00
|
|
|
{ LOG_XKF9_MSG, sizeof(log_NKF4), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"XKF9","QcccccfbbHBHHb","TimeUS,SV,SP,SH,SM,SVT,errRP,OFN,OFE,FS,TS,SS,GPS,PI", "s-----???-----", "F-----???-----" }, \
|
2016-07-14 02:08:43 -03:00
|
|
|
{ LOG_XKF10_MSG, sizeof(log_RngBcnDebug), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"XKF0","QBccCCcccccccc","TimeUS,ID,rng,innov,SIV,TR,BPN,BPE,BPD,OFH,OFL,OFN,OFE,OFD", "s-m---mmmmmmmm", "F-B---BBBBBBBB" }, \
|
2019-07-20 03:37:11 -03:00
|
|
|
{ LOG_XKF11_MSG, sizeof(log_EKF1), \
|
|
|
|
"XK11","QccCfffffffccce","TimeUS,Roll,Pitch,Yaw,VN,VE,VD,dPD,PN,PE,PD,GX,GY,GZ,OH", "sddhnnn-mmmkkkm", "FBBB000-000BBBB" }, \
|
|
|
|
{ LOG_XKF12_MSG, sizeof(log_NKF2a), \
|
|
|
|
"XK12","QccccchhhhhhB","TimeUS,AX,AY,AZ,VWN,VWE,MN,ME,MD,MX,MY,MZ,MI", "s---nnGGGGGG-", "F---BBCCCCCC-" }, \
|
|
|
|
{ LOG_XKF13_MSG, sizeof(log_NKF3), \
|
|
|
|
"XK13","Qcccccchhhcc","TimeUS,IVN,IVE,IVD,IPN,IPE,IPD,IMX,IMY,IMZ,IYAW,IVT", "snnnmmmGGGd?", "FBBBBBBCCCBB" }, \
|
|
|
|
{ LOG_XKF14_MSG, sizeof(log_NKF4), \
|
|
|
|
"XK14","QcccccfbbHBHHb","TimeUS,SV,SP,SH,SM,SVT,errRP,OFN,OFE,FS,TS,SS,GPS,PI", "s-----???-----", "F-----???-----" }, \
|
2015-12-07 20:51:46 -04:00
|
|
|
{ LOG_XKQ1_MSG, sizeof(log_Quaternion), "XKQ1", QUAT_FMT, QUAT_LABELS, QUAT_UNITS, QUAT_MULTS }, \
|
|
|
|
{ LOG_XKQ2_MSG, sizeof(log_Quaternion), "XKQ2", QUAT_FMT, QUAT_LABELS, QUAT_UNITS, QUAT_MULTS }, \
|
2019-07-20 03:37:11 -03:00
|
|
|
{ LOG_XKQ3_MSG, sizeof(log_Quaternion), "XKQ3", QUAT_FMT, QUAT_LABELS, QUAT_UNITS, QUAT_MULTS }, \
|
2017-03-22 00:46:33 -03:00
|
|
|
{ LOG_XKFD_MSG, sizeof(log_ekfBodyOdomDebug), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"XKFD","Qffffff","TimeUS,IX,IY,IZ,IVX,IVY,IVZ", "s------", "F------" }, \
|
2017-05-20 23:13:08 -03:00
|
|
|
{ LOG_XKV1_MSG, sizeof(log_ekfStateVar), \
|
2018-03-01 01:45:18 -04:00
|
|
|
"XKV1","Qffffffffffff","TimeUS,V00,V01,V02,V03,V04,V05,V06,V07,V08,V09,V10,V11", "s------------", "F------------" }, \
|
2017-05-20 23:13:08 -03:00
|
|
|
{ LOG_XKV2_MSG, sizeof(log_ekfStateVar), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"XKV2","Qffffffffffff","TimeUS,V12,V13,V14,V15,V16,V17,V18,V19,V20,V21,V22,V23", "s------------", "F------------" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_TERRAIN_MSG, sizeof(log_TERRAIN), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"TERR","QBLLHffHH","TimeUS,Status,Lat,Lng,Spacing,TerrH,CHeight,Pending,Loaded", "s-DU-mm--", "F-GG-00--" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_GPS_UBX1_MSG, sizeof(log_Ubx1), \
|
2018-03-01 01:45:18 -04:00
|
|
|
"UBX1", "QBHBBHI", "TimeUS,Instance,noisePerMS,jamInd,aPower,agcCnt,config", "s------", "F------" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_GPS_UBX2_MSG, sizeof(log_Ubx2), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"UBX2", "QBbBbB", "TimeUS,Instance,ofsI,magI,ofsQ,magQ", "s-----", "F-----" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_GPS2_UBX1_MSG, sizeof(log_Ubx1), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"UBY1", "QBHBBHI", "TimeUS,Instance,noisePerMS,jamInd,aPower,agcCnt,config", "s------", "F------" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_GPS2_UBX2_MSG, sizeof(log_Ubx2), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"UBY2", "QBbBbB", "TimeUS,Instance,ofsI,magI,ofsQ,magQ", "s-----", "F-----" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_GPS_RAW_MSG, sizeof(log_GPS_RAW), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"GRAW", "QIHBBddfBbB", "TimeUS,WkMS,Week,numSV,sv,cpMes,prMes,doMes,mesQI,cno,lli", "s--S-------", "F--0-------" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_GPS_RAWH_MSG, sizeof(log_GPS_RAWH), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"GRXH", "QdHbBB", "TimeUS,rcvTime,week,leapS,numMeas,recStat", "s-----", "F-----" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_GPS_RAWS_MSG, sizeof(log_GPS_RAWS), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"GRXS", "QddfBBBHBBBBB", "TimeUS,prMes,cpMes,doMes,gnss,sv,freq,lock,cno,prD,cpD,doD,trk", "s------------", "F------------" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_GPS_SBF_EVENT_MSG, sizeof(log_GPS_SBF_EVENT), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"SBFE", "QIHBBdddfffff", "TimeUS,TOW,WN,Mode,Err,Lat,Lng,Height,Undul,Vn,Ve,Vu,COG", "s----DUm-nnnh", "F----000-0000" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_ESC1_MSG, sizeof(log_Esc), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"ESC1", ESC_FMT, ESC_LABELS, ESC_UNITS, ESC_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_ESC2_MSG, sizeof(log_Esc), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"ESC2", ESC_FMT, ESC_LABELS, ESC_UNITS, ESC_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_ESC3_MSG, sizeof(log_Esc), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"ESC3", ESC_FMT, ESC_LABELS, ESC_UNITS, ESC_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_ESC4_MSG, sizeof(log_Esc), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"ESC4", ESC_FMT, ESC_LABELS, ESC_UNITS, ESC_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_ESC5_MSG, sizeof(log_Esc), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"ESC5", ESC_FMT, ESC_LABELS, ESC_UNITS, ESC_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_ESC6_MSG, sizeof(log_Esc), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"ESC6", ESC_FMT, ESC_LABELS, ESC_UNITS, ESC_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_ESC7_MSG, sizeof(log_Esc), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"ESC7", ESC_FMT, ESC_LABELS, ESC_UNITS, ESC_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_ESC8_MSG, sizeof(log_Esc), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"ESC8", ESC_FMT, ESC_LABELS, ESC_UNITS, ESC_MULTS }, \
|
2020-01-07 17:36:42 -04:00
|
|
|
{ LOG_CSRV_MSG, sizeof(log_CSRV), \
|
|
|
|
"CSRV","QBfffB","TimeUS,Id,Pos,Force,Speed,Pow", "s#---%", "F-0000" }, \
|
2020-01-04 00:56:44 -04:00
|
|
|
{ LOG_CESC_MSG, sizeof(log_CESC), \
|
|
|
|
"CESC","QBIfffiB","TimeUS,Id,ECnt,Voltage,Curr,Temp,RPM,Pow", "s#-vAOq%", "F-000000" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_COMPASS2_MSG, sizeof(log_Compass), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"MAG2",MAG_FMT, MAG_LABELS, MAG_UNITS, MAG_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_COMPASS3_MSG, sizeof(log_Compass), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"MAG3",MAG_FMT, MAG_LABELS, MAG_UNITS, MAG_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_ACC1_MSG, sizeof(log_ACCEL), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"ACC1", ACC_FMT, ACC_LABELS, ACC_UNITS, ACC_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_ACC2_MSG, sizeof(log_ACCEL), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"ACC2", ACC_FMT, ACC_LABELS, ACC_UNITS, ACC_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_ACC3_MSG, sizeof(log_ACCEL), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"ACC3", ACC_FMT, ACC_LABELS, ACC_UNITS, ACC_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_GYR1_MSG, sizeof(log_GYRO), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"GYR1", GYR_FMT, GYR_LABELS, GYR_UNITS, GYR_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_GYR2_MSG, sizeof(log_GYRO), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"GYR2", GYR_FMT, GYR_LABELS, GYR_UNITS, GYR_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_GYR3_MSG, sizeof(log_GYRO), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"GYR3", GYR_FMT, GYR_LABELS, GYR_UNITS, GYR_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_PIDR_MSG, sizeof(log_PID), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"PIDR", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_PIDP_MSG, sizeof(log_PID), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"PIDP", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_PIDY_MSG, sizeof(log_PID), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"PIDY", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_PIDA_MSG, sizeof(log_PID), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"PIDA", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_PIDS_MSG, sizeof(log_PID), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"PIDS", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, \
|
2017-10-12 19:26:43 -03:00
|
|
|
{ LOG_DSTL_MSG, sizeof(log_DSTL), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"DSTL", "QBfLLeccfeffff", "TimeUS,Stg,THdg,Lat,Lng,Alt,XT,Travel,L1I,Loiter,Des,P,I,D", "s??DUm--------", "F??000--------" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_BAR2_MSG, sizeof(log_BARO), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"BAR2", BARO_FMT, BARO_LABELS, BARO_UNITS, BARO_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_BAR3_MSG, sizeof(log_BARO), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"BAR3", BARO_FMT, BARO_LABELS, BARO_UNITS, BARO_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_VIBE_MSG, sizeof(log_Vibe), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"VIBE", "QfffIII", "TimeUS,VibeX,VibeY,VibeZ,Clip0,Clip1,Clip2", "s------", "F------" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_IMUDT_MSG, sizeof(log_IMUDT), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"IMT",IMT_FMT,IMT_LABELS, IMT_UNITS, IMT_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_IMUDT2_MSG, sizeof(log_IMUDT), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"IMT2",IMT_FMT,IMT_LABELS, IMT_UNITS, IMT_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_IMUDT3_MSG, sizeof(log_IMUDT), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"IMT3",IMT_FMT,IMT_LABELS, IMT_UNITS, IMT_MULTS }, \
|
2017-09-01 08:05:16 -03:00
|
|
|
{ LOG_ISBH_MSG, sizeof(log_ISBH), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"ISBH",ISBH_FMT,ISBH_LABELS,ISBH_UNITS,ISBH_MULTS }, \
|
2017-09-01 08:05:16 -03:00
|
|
|
{ LOG_ISBD_MSG, sizeof(log_ISBD), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"ISBD",ISBD_FMT,ISBD_LABELS, ISBD_UNITS, ISBD_MULTS }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_ORGN_MSG, sizeof(log_ORGN), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"ORGN","QBLLe","TimeUS,Type,Lat,Lng,Alt", "s-DUm", "F-GGB" }, \
|
2017-08-25 04:18:26 -03:00
|
|
|
{ LOG_DF_FILE_STATS, sizeof(log_DSF), \
|
2018-08-07 07:22:21 -03:00
|
|
|
"DSF", "QIHIIII", "TimeUS,Dp,Blk,Bytes,FMn,FMx,FAv", "s--b---", "F--0---" }, \
|
2015-11-05 19:50:54 -04:00
|
|
|
{ LOG_RPM_MSG, sizeof(log_RPM), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"RPM", "Qff", "TimeUS,rpm1,rpm2", "sqq", "F00" }, \
|
2016-01-04 18:49:11 -04:00
|
|
|
{ LOG_GIMBAL1_MSG, sizeof(log_Gimbal1), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"GMB1", "Iffffffffff", "TimeMS,dt,dax,day,daz,dvx,dvy,dvz,jx,jy,jz", "ssrrrEEELLL", "CC000000000" }, \
|
2016-01-04 18:49:11 -04:00
|
|
|
{ LOG_GIMBAL2_MSG, sizeof(log_Gimbal2), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"GMB2", "IBfffffffff", "TimeMS,es,ex,ey,ez,rx,ry,rz,tx,ty,tz", "s-rrrEEELLL", "C-000000000" }, \
|
2016-01-04 18:49:11 -04:00
|
|
|
{ LOG_GIMBAL3_MSG, sizeof(log_Gimbal3), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"GMB3", "Ihhh", "TimeMS,rl_torque_cmd,el_torque_cmd,az_torque_cmd", "s???", "C???" }, \
|
2016-03-24 22:11:11 -03:00
|
|
|
{ LOG_RATE_MSG, sizeof(log_Rate), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"RATE", "Qffffffffffff", "TimeUS,RDes,R,ROut,PDes,P,POut,YDes,Y,YOut,ADes,A,AOut", "skk-kk-kk-oo-", "F?????????BB-" }, \
|
2016-07-03 23:14:26 -03:00
|
|
|
{ LOG_RALLY_MSG, sizeof(log_Rally), \
|
2018-03-01 01:45:18 -04:00
|
|
|
"RALY", "QBBLLh", "TimeUS,Tot,Seq,Lat,Lng,Alt", "s--DUm", "F--GGB" }, \
|
2019-02-06 22:30:09 -04:00
|
|
|
{ LOG_MAV_MSG, sizeof(log_MAV), \
|
|
|
|
"MAV", "QBHHH", "TimeUS,chan,txp,rxp,rxdp", "s#---", "F-000" }, \
|
2017-04-03 23:47:04 -03:00
|
|
|
{ LOG_VISUALODOM_MSG, sizeof(log_VisualOdom), \
|
2018-09-02 09:27:58 -03:00
|
|
|
"VISO", "Qffffffff", "TimeUS,dt,AngDX,AngDY,AngDZ,PosDX,PosDY,PosDZ,conf", "ssrrrmmm-", "FF000000-" }, \
|
|
|
|
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow), \
|
2019-02-05 01:00:28 -04:00
|
|
|
"OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY", "s-EEEE", "F-0000" }, \
|
|
|
|
{ LOG_WHEELENCODER_MSG, sizeof(log_WheelEncoder), \
|
2019-02-23 15:31:20 -04:00
|
|
|
"WENC", "Qfbfb", "TimeUS,Dist0,Qual0,Dist1,Qual1", "sm-m-", "F0-0-" }, \
|
|
|
|
{ LOG_ADSB_MSG, sizeof(log_ADSB), \
|
|
|
|
"ADSB", "QIiiiHHhH", "TimeUS,ICAO_address,Lat,Lng,Alt,Heading,Hor_vel,Ver_vel,Squark", "s-DUmhnn-", "F-GGCBCC-" }
|
2018-03-01 01:45:18 -04:00
|
|
|
|
2015-11-05 19:50:54 -04:00
|
|
|
|
2015-11-09 18:10:46 -04:00
|
|
|
#define LOG_SBP_STRUCTURES \
|
|
|
|
{ LOG_MSG_SBPHEALTH, sizeof(log_SbpHealth), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"SBPH", "QIII", "TimeUS,CrcError,LastInject,IARhyp", "s---", "F---" }, \
|
2017-06-26 12:41:24 -03:00
|
|
|
{ LOG_MSG_SBPRAWH, sizeof(log_SbpRAWH), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"SBRH", "QQQQQQQQ", "TimeUS,msg_flag,1,2,3,4,5,6", "s--b----", "F--0----" }, \
|
2017-06-26 12:41:24 -03:00
|
|
|
{ LOG_MSG_SBPRAWM, sizeof(log_SbpRAWM), \
|
2015-12-07 20:51:46 -04:00
|
|
|
"SBRM", "QQQQQQQQQQQQQQQ", "TimeUS,msg_flag,1,2,3,4,5,6,7,8,9,10,11,12,13", "s??????????????", "F??????????????" }, \
|
2019-02-01 07:29:43 -04:00
|
|
|
{ LOG_EVENT_MSG, sizeof(log_Event), \
|
|
|
|
"EV", "QB", "TimeUS,Id", "s-", "F-" }, \
|
2017-06-29 11:17:10 -03:00
|
|
|
{ LOG_MSG_SBPEVENT, sizeof(log_SbpEvent), \
|
2019-03-24 22:04:59 -03:00
|
|
|
"SBRE", "QHIiBB", "TimeUS,GWk,GMS,ns_residual,level,quality", "s?????", "F?????" }, \
|
2019-05-03 08:25:08 -03:00
|
|
|
{ LOG_ARM_DISARM_MSG, sizeof(log_Arm_Disarm), \
|
|
|
|
"ARM", "QBH", "TimeUS,ArmState,ArmChecks", "s--", "F--" }, \
|
2019-03-24 22:04:59 -03:00
|
|
|
{ LOG_ERROR_MSG, sizeof(log_Error), \
|
|
|
|
"ERR", "QBB", "TimeUS,Subsys,ECode", "s--", "F--" }
|
|
|
|
|
2015-11-09 18:10:46 -04:00
|
|
|
#define LOG_COMMON_STRUCTURES LOG_BASE_STRUCTURES, LOG_EXTRA_STRUCTURES, LOG_SBP_STRUCTURES
|
2015-11-05 19:50:54 -04:00
|
|
|
|
2018-03-07 19:13:26 -04:00
|
|
|
// message types 0 to 63 reserved for vehicle specific use
|
2015-11-05 19:50:54 -04:00
|
|
|
|
|
|
|
// message types for common messages
|
2018-03-31 11:40:01 -03:00
|
|
|
enum LogMessages : uint8_t {
|
2018-03-07 19:13:26 -04:00
|
|
|
LOG_NKF1_MSG = 64,
|
|
|
|
LOG_NKF2_MSG,
|
|
|
|
LOG_NKF3_MSG,
|
|
|
|
LOG_NKF4_MSG,
|
|
|
|
LOG_NKF5_MSG,
|
|
|
|
LOG_NKF6_MSG,
|
|
|
|
LOG_NKF7_MSG,
|
|
|
|
LOG_NKF8_MSG,
|
|
|
|
LOG_NKF9_MSG,
|
|
|
|
LOG_NKF10_MSG,
|
2019-07-20 03:37:11 -03:00
|
|
|
LOG_NKF11_MSG,
|
|
|
|
LOG_NKF12_MSG,
|
|
|
|
LOG_NKF13_MSG,
|
|
|
|
LOG_NKF14_MSG,
|
2018-03-07 19:13:26 -04:00
|
|
|
LOG_NKQ1_MSG,
|
|
|
|
LOG_NKQ2_MSG,
|
2019-07-20 03:37:11 -03:00
|
|
|
LOG_NKQ3_MSG,
|
2018-03-07 19:13:26 -04:00
|
|
|
LOG_XKF1_MSG,
|
|
|
|
LOG_XKF2_MSG,
|
|
|
|
LOG_XKF3_MSG,
|
|
|
|
LOG_XKF4_MSG,
|
|
|
|
LOG_XKF5_MSG,
|
|
|
|
LOG_XKF6_MSG,
|
|
|
|
LOG_XKF7_MSG,
|
|
|
|
LOG_XKF8_MSG,
|
|
|
|
LOG_XKF9_MSG,
|
|
|
|
LOG_XKF10_MSG,
|
2019-07-20 03:37:11 -03:00
|
|
|
LOG_XKF11_MSG,
|
|
|
|
LOG_XKF12_MSG,
|
|
|
|
LOG_XKF13_MSG,
|
|
|
|
LOG_XKF14_MSG,
|
2018-03-07 19:13:26 -04:00
|
|
|
LOG_XKQ1_MSG,
|
|
|
|
LOG_XKQ2_MSG,
|
2019-07-20 03:37:11 -03:00
|
|
|
LOG_XKQ3_MSG,
|
2018-03-07 19:13:26 -04:00
|
|
|
LOG_XKFD_MSG,
|
|
|
|
LOG_XKV1_MSG,
|
|
|
|
LOG_XKV2_MSG,
|
|
|
|
|
|
|
|
LOG_FORMAT_MSG = 128, // this must remain #128
|
|
|
|
|
2015-11-05 19:50:54 -04:00
|
|
|
LOG_PARAMETER_MSG,
|
|
|
|
LOG_GPS_MSG,
|
|
|
|
LOG_GPS2_MSG,
|
2017-03-10 02:48:51 -04:00
|
|
|
LOG_GPSB_MSG,
|
2015-11-05 19:50:54 -04:00
|
|
|
LOG_IMU_MSG,
|
|
|
|
LOG_MESSAGE_MSG,
|
|
|
|
LOG_RCIN_MSG,
|
|
|
|
LOG_RCOUT_MSG,
|
|
|
|
LOG_RSSI_MSG,
|
|
|
|
LOG_IMU2_MSG,
|
|
|
|
LOG_BARO_MSG,
|
|
|
|
LOG_POWR_MSG,
|
|
|
|
LOG_AHR2_MSG,
|
|
|
|
LOG_SIMSTATE_MSG,
|
|
|
|
LOG_CMD_MSG,
|
2019-08-22 22:21:39 -03:00
|
|
|
LOG_MAVLINK_COMMAND_MSG,
|
2015-11-05 19:50:54 -04:00
|
|
|
LOG_RADIO_MSG,
|
|
|
|
LOG_ATRP_MSG,
|
|
|
|
LOG_CAMERA_MSG,
|
|
|
|
LOG_IMU3_MSG,
|
|
|
|
LOG_TERRAIN_MSG,
|
|
|
|
LOG_GPS_UBX1_MSG,
|
|
|
|
LOG_GPS_UBX2_MSG,
|
|
|
|
LOG_GPS2_UBX1_MSG,
|
|
|
|
LOG_GPS2_UBX2_MSG,
|
|
|
|
LOG_ESC1_MSG,
|
|
|
|
LOG_ESC2_MSG,
|
|
|
|
LOG_ESC3_MSG,
|
|
|
|
LOG_ESC4_MSG,
|
|
|
|
LOG_ESC5_MSG,
|
|
|
|
LOG_ESC6_MSG,
|
|
|
|
LOG_ESC7_MSG,
|
|
|
|
LOG_ESC8_MSG,
|
2020-01-07 17:36:42 -04:00
|
|
|
LOG_CSRV_MSG,
|
2020-01-04 00:56:44 -04:00
|
|
|
LOG_CESC_MSG,
|
2015-11-05 19:50:54 -04:00
|
|
|
LOG_BAR2_MSG,
|
|
|
|
LOG_ARSP_MSG,
|
|
|
|
LOG_ATTITUDE_MSG,
|
|
|
|
LOG_CURRENT_MSG,
|
2016-06-02 18:00:57 -03:00
|
|
|
LOG_CURRENT2_MSG,
|
2018-09-12 20:39:30 -03:00
|
|
|
LOG_CURRENT3_MSG,
|
|
|
|
LOG_CURRENT4_MSG,
|
|
|
|
LOG_CURRENT5_MSG,
|
|
|
|
LOG_CURRENT6_MSG,
|
|
|
|
LOG_CURRENT7_MSG,
|
|
|
|
LOG_CURRENT8_MSG,
|
|
|
|
LOG_CURRENT9_MSG,
|
2017-05-30 22:44:40 -03:00
|
|
|
LOG_CURRENT_CELLS_MSG,
|
|
|
|
LOG_CURRENT_CELLS2_MSG,
|
2018-09-12 20:39:30 -03:00
|
|
|
LOG_CURRENT_CELLS3_MSG,
|
|
|
|
LOG_CURRENT_CELLS4_MSG,
|
|
|
|
LOG_CURRENT_CELLS5_MSG,
|
|
|
|
LOG_CURRENT_CELLS6_MSG,
|
|
|
|
LOG_CURRENT_CELLS7_MSG,
|
|
|
|
LOG_CURRENT_CELLS8_MSG,
|
|
|
|
LOG_CURRENT_CELLS9_MSG,
|
2015-11-05 19:50:54 -04:00
|
|
|
LOG_COMPASS_MSG,
|
|
|
|
LOG_COMPASS2_MSG,
|
|
|
|
LOG_COMPASS3_MSG,
|
|
|
|
LOG_MODE_MSG,
|
|
|
|
LOG_GPS_RAW_MSG,
|
|
|
|
LOG_GPS_RAWH_MSG,
|
|
|
|
LOG_GPS_RAWS_MSG,
|
|
|
|
LOG_GPS_SBF_EVENT_MSG,
|
|
|
|
LOG_ACC1_MSG,
|
|
|
|
LOG_ACC2_MSG,
|
|
|
|
LOG_ACC3_MSG,
|
|
|
|
LOG_GYR1_MSG,
|
|
|
|
LOG_GYR2_MSG,
|
|
|
|
LOG_GYR3_MSG,
|
|
|
|
LOG_POS_MSG,
|
|
|
|
LOG_PIDR_MSG,
|
|
|
|
LOG_PIDP_MSG,
|
|
|
|
LOG_PIDY_MSG,
|
|
|
|
LOG_PIDA_MSG,
|
|
|
|
LOG_PIDS_MSG,
|
2017-10-12 19:26:43 -03:00
|
|
|
LOG_DSTL_MSG,
|
2015-11-05 19:50:54 -04:00
|
|
|
LOG_VIBE_MSG,
|
|
|
|
LOG_IMUDT_MSG,
|
|
|
|
LOG_IMUDT2_MSG,
|
|
|
|
LOG_IMUDT3_MSG,
|
|
|
|
LOG_ORGN_MSG,
|
|
|
|
LOG_RPM_MSG,
|
|
|
|
LOG_GPA_MSG,
|
|
|
|
LOG_GPA2_MSG,
|
2017-03-10 02:48:51 -04:00
|
|
|
LOG_GPAB_MSG,
|
2015-11-05 19:50:54 -04:00
|
|
|
LOG_RFND_MSG,
|
|
|
|
LOG_BAR3_MSG,
|
2019-02-11 04:38:01 -04:00
|
|
|
LOG_MAV_STATS,
|
2015-12-07 20:51:46 -04:00
|
|
|
LOG_FORMAT_UNITS_MSG,
|
|
|
|
LOG_UNIT_MSG,
|
|
|
|
LOG_MULT_MSG,
|
2015-11-09 18:10:46 -04:00
|
|
|
|
|
|
|
LOG_MSG_SBPHEALTH,
|
|
|
|
LOG_MSG_SBPLLH,
|
|
|
|
LOG_MSG_SBPBASELINE,
|
|
|
|
LOG_MSG_SBPTRACKING1,
|
|
|
|
LOG_MSG_SBPTRACKING2,
|
2017-06-26 12:41:24 -03:00
|
|
|
LOG_MSG_SBPRAWH,
|
|
|
|
LOG_MSG_SBPRAWM,
|
2017-06-29 11:17:10 -03:00
|
|
|
LOG_MSG_SBPEVENT,
|
2016-01-06 20:29:52 -04:00
|
|
|
LOG_TRIGGER_MSG,
|
2015-11-09 18:10:46 -04:00
|
|
|
|
2016-01-04 18:49:11 -04:00
|
|
|
LOG_GIMBAL1_MSG,
|
|
|
|
LOG_GIMBAL2_MSG,
|
|
|
|
LOG_GIMBAL3_MSG,
|
2016-03-24 22:11:11 -03:00
|
|
|
LOG_RATE_MSG,
|
2016-07-03 23:14:26 -03:00
|
|
|
LOG_RALLY_MSG,
|
2017-04-03 23:47:04 -03:00
|
|
|
LOG_VISUALODOM_MSG,
|
2017-04-09 08:17:17 -03:00
|
|
|
LOG_AOA_SSA_MSG,
|
2017-04-18 11:43:03 -03:00
|
|
|
LOG_BEACON_MSG,
|
2017-07-14 14:00:13 -03:00
|
|
|
LOG_PROXIMITY_MSG,
|
2017-08-25 04:18:26 -03:00
|
|
|
LOG_DF_FILE_STATS,
|
2017-07-26 14:09:33 -03:00
|
|
|
LOG_SRTL_MSG,
|
2017-09-01 08:05:16 -03:00
|
|
|
LOG_ISBH_MSG,
|
|
|
|
LOG_ISBD_MSG,
|
2017-11-03 03:37:40 -03:00
|
|
|
LOG_ASP2_MSG,
|
2017-11-15 23:20:17 -04:00
|
|
|
LOG_PERFORMANCE_MSG,
|
2018-09-02 09:27:58 -03:00
|
|
|
LOG_OPTFLOW_MSG,
|
2019-02-01 07:29:43 -04:00
|
|
|
LOG_EVENT_MSG,
|
2019-02-05 01:00:28 -04:00
|
|
|
LOG_WHEELENCODER_MSG,
|
2019-02-06 22:30:09 -04:00
|
|
|
LOG_MAV_MSG,
|
2019-03-24 22:04:59 -03:00
|
|
|
LOG_ERROR_MSG,
|
2019-02-23 15:31:20 -04:00
|
|
|
LOG_ADSB_MSG,
|
2019-05-03 08:25:08 -03:00
|
|
|
LOG_ARM_DISARM_MSG,
|
2019-08-05 03:22:05 -03:00
|
|
|
LOG_OA_BENDYRULER_MSG,
|
|
|
|
LOG_OA_DIJKSTRA_MSG,
|
2019-03-24 22:04:59 -03:00
|
|
|
|
2017-11-15 23:20:17 -04:00
|
|
|
_LOG_LAST_MSG_
|
2015-11-05 19:50:54 -04:00
|
|
|
};
|
|
|
|
|
2017-11-15 23:20:17 -04:00
|
|
|
static_assert(_LOG_LAST_MSG_ <= 255, "Too many message formats");
|
|
|
|
|
2015-11-05 19:50:54 -04:00
|
|
|
enum LogOriginType {
|
|
|
|
ekf_origin = 0,
|
|
|
|
ahrs_home = 1
|
|
|
|
};
|