2016-02-17 21:25:53 -04:00
# pragma once
2015-11-05 19:50:54 -04:00
2020-11-05 19:26:16 -04:00
# include <AP_Common/AP_Common.h>
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
2021-03-17 05:35:40 -03:00
{ ' a ' , " Ah " } , // Ampere hours
2017-09-17 18:47:11 -03:00
{ ' 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
2020-11-07 08:37:13 -04: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
2020-11-05 19:26:16 -04:00
# include <AP_DAL/LogStructure.h>
# include <AP_NavEKF2/LogStructure.h>
# include <AP_NavEKF3/LogStructure.h>
2021-02-09 19:08:38 -04:00
# include <AP_GPS/LogStructure.h>
2021-02-17 18:34:13 -04:00
# include <AP_NavEKF/LogStructure.h>
2021-01-11 21:43:14 -04:00
# include <AP_BattMonitor/LogStructure.h>
2021-02-09 15:05:03 -04:00
# include <AP_InertialSensor/LogStructure.h>
2021-01-08 23:45:38 -04:00
# include <AP_AHRS/LogStructure.h>
2021-01-22 15:51:48 -04:00
# include <AP_Camera/LogStructure.h>
2021-02-02 00:08:50 -04:00
# include <AP_Baro/LogStructure.h>
2021-02-02 22:12:58 -04:00
# include <AP_VisualOdom/LogStructure.h>
2021-04-12 07:40:50 -03:00
# include <AC_PrecLand/LogStructure.h>
2021-01-22 03:24:54 -04:00
# include <AC_Avoidance/LogStructure.h>
2021-03-17 05:35:40 -03:00
# include <AP_ESC_Telem/LogStructure.h>
2021-01-08 23:45:38 -04:00
2019-06-04 03:28:01 -03:00
// 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_Message {
LOG_PACKET_HEADER ;
uint64_t time_us ;
char msg [ 64 ] ;
} ;
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 ;
} ;
2020-08-19 05:56:50 -03:00
struct PACKED log_RCIN2 {
LOG_PACKET_HEADER ;
uint64_t time_us ;
uint16_t chan15 ;
uint16_t chan16 ;
2021-05-15 00:45:43 -03:00
uint16_t override_mask ;
2020-08-19 05:56:50 -03:00
} ;
2015-11-05 19:50:54 -04:00
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 ;
2020-02-20 01:13:50 -04:00
uint8_t flags ;
2020-03-23 23:15:03 -03:00
uint16_t stream_slowdown_ms ;
2020-04-14 19:54:22 -03:00
uint16_t times_full ;
2019-02-06 22:30:09 -04:00
} ;
2015-11-05 19:50:54 -04:00
struct PACKED log_RSSI {
LOG_PACKET_HEADER ;
uint64_t time_us ;
float RXRSSI ;
} ;
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_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 ;
2020-07-19 21:34:43 -03:00
uint16_t accumulated_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_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_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 ;
2020-05-10 04:16:23 -03:00
float Dmod ;
2021-04-04 06:49:09 -03:00
float slew_rate ;
2021-01-02 14:02:46 -04:00
uint8_t limit ;
2015-11-05 19:50:54 -04:00
} ;
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 ;
} ;
2020-11-01 21:46:43 -04:00
struct PACKED log_MAG {
2015-11-05 19:50:54 -04:00
LOG_PACKET_HEADER ;
uint64_t time_us ;
2020-11-01 21:46:43 -04:00
uint8_t instance ;
2015-11-05 19:50:54 -04:00
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 ;
} ;
2020-01-04 00:25:55 -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-11-18 18:52:49 -04:00
struct PACKED log_ARSP {
2015-11-05 19:50:54 -04:00
LOG_PACKET_HEADER ;
uint64_t time_us ;
2020-11-18 18:52:49 -04:00
uint8_t instance ;
2015-11-05 19:50:54 -04:00
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
} ;
2019-02-11 04:38:01 -04:00
struct PACKED log_MAV_Stats {
2015-11-10 02:34:31 -04:00
LOG_PACKET_HEADER ;
2020-04-03 22:37:36 -03:00
uint64_t timestamp ;
2015-11-10 02:34:31 -04:00
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_RPM {
LOG_PACKET_HEADER ;
uint64_t time_us ;
float rpm1 ;
float rpm2 ;
} ;
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-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 ;
2021-02-12 04:31:30 -04:00
uint8_t instance ;
2017-07-14 14:00:13 -03:00
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 ;
} ;
2021-02-12 04:31:30 -04:00
struct PACKED log_Proximity_raw {
LOG_PACKET_HEADER ;
uint64_t time_us ;
uint8_t instance ;
float raw_dist0 ;
float raw_dist45 ;
float raw_dist90 ;
float raw_dist135 ;
float raw_dist180 ;
float raw_dist225 ;
float raw_dist270 ;
float raw_dist315 ;
} ;
2017-07-14 14:00:13 -03:00
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 ;
2020-10-09 15:55:03 -03:00
uint16_t internal_error_last_line ;
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 ;
} ;
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 ;
2020-02-11 21:25:28 -04:00
uint32_t arm_checks ;
2020-01-07 01:04:31 -04:00
uint8_t forced ;
uint8_t method ;
2019-05-03 08:25:08 -03:00
} ;
2015-11-09 18:10:46 -04:00
2020-07-24 02:59:41 -03:00
struct PACKED log_Winch {
LOG_PACKET_HEADER ;
uint64_t time_us ;
uint8_t healthy ;
uint8_t thread_end ;
uint8_t moving ;
uint8_t clutch ;
uint8_t mode ;
float desired_length ;
float length ;
float desired_rate ;
uint16_t tension ;
float voltage ;
int8_t temp ;
} ;
2020-09-09 04:16:39 -03:00
struct PACKED log_PSC {
LOG_PACKET_HEADER ;
uint64_t time_us ;
float pos_target_x ;
float pos_target_Y ;
float position_x ;
float position_y ;
float vel_target_x ;
float vel_target_y ;
float velocity_x ;
float velocity_y ;
float accel_target_x ;
float accel_target_y ;
float accel_x ;
float accel_y ;
} ;
2021-01-29 00:42:26 -04:00
// position controller z-axis logging
struct PACKED log_PSCZ {
LOG_PACKET_HEADER ;
uint64_t time_us ;
float pos_target_z ;
float pos_z ;
float vel_desired_z ;
float vel_target_z ;
float vel_z ;
float accel_desired_z ;
float accel_target_z ;
float accel_z ;
float throttle_out ;
} ;
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
2021-04-04 06:49:09 -03:00
# define PID_LABELS "TimeUS,Tar,Act,Err,P,I,D,FF,Dmod,SRate,Limit"
# define PID_FMT "QfffffffffB"
# define PID_UNITS "s----------"
# define PID_MULTS "F----------"
2017-04-05 03:37:34 -03:00
2020-04-12 04:19:56 -03:00
// @LoggerMessage: ADSB
// @Description: Automatic Dependant Serveillance - Broadcast detected vehicle information
// @Field: TimeUS: Time since system startup
// @Field: ICAO_address: Transponder address
// @Field: Lat: Vehicle latitude
// @Field: Lng: Vehicle longitude
// @Field: Alt: Vehicle altitude
// @Field: Heading: Vehicle heading
// @Field: Hor_vel: Vehicle horizontal velocity
// @Field: Ver_vel: Vehicle vertical velocity
// @Field: Squark: Transponder squawk code
AP_Logger: add documentation for ACC1,ACC2,ACC3,DMS,GPA,GPA2,GPS2,GYR1,GYR2,GYR3,MAVC,PM
2020-04-03 22:32:14 -03:00
// @LoggerMessage: ARM
// @Description: Arming status changes
// @Field: TimeUS: Time since system startup
// @Field: ArmState: true if vehicle is now armed
// @Field: ArmChecks: arming bitmask at time of arming
// @Field: Forced: true if arm/disarm was forced
// @Field: Method: method used for arming
2020-11-18 18:52:49 -04:00
// @LoggerMessage: ARSP
2020-04-05 07:50:34 -03:00
// @Description: Airspeed sensor data
// @Field: TimeUS: Time since system startup
2020-11-18 18:52:49 -04:00
// @Field: I: Airspeed sensor instance number
2020-04-05 07:50:34 -03:00
// @Field: Airspeed: Current airspeed
// @Field: DiffPress: Pressure difference between static and dynamic port
// @Field: Temp: Temperature used for calculation
// @Field: RawPress: Raw pressure less offset
// @Field: Offset: Offset from parameter
// @Field: U: True if sensor is being used
2020-11-23 23:26:03 -04:00
// @Field: H: True if sensor is healthy
2020-04-07 04:35:05 -03:00
// @Field: Hfp: Probability sensor has failed
2020-04-05 07:50:34 -03:00
// @Field: Pri: True if sensor is the primary sensor
2020-04-12 04:19:56 -03:00
// @LoggerMessage: BCN
2020-12-17 08:40:55 -04:00
// @Description: Beacon information
2020-04-12 04:19:56 -03:00
// @Field: TimeUS: Time since system startup
// @Field: Health: True if beacon sensor is healthy
// @Field: Cnt: Number of beacons being used
// @Field: D0: Distance to first beacon
// @Field: D1: Distance to second beacon
// @Field: D2: Distance to third beacon
2020-12-17 08:40:55 -04:00
// @Field: D3: Distance to fourth beacon
2020-04-12 04:19:56 -03:00
// @Field: PosX: Calculated beacon position, x-axis
// @Field: PosY: Calculated beacon position, y-axis
// @Field: PosZ: Calculated beacon position, z-axis
2020-04-05 07:50:34 -03:00
// @LoggerMessage: CMD
// @Description: Executed mission command information
// @Field: TimeUS: Time since system startup
// @Field: CTot: Total number of mission commands
// @Field: CNum: This command's offset in mission
// @Field: CId: Command type
// @Field: Prm1: Parameter 1
// @Field: Prm2: Parameter 2
// @Field: Prm3: Parameter 3
// @Field: Prm4: Parameter 4
// @Field: Lat: Command latitude
// @Field: Lng: Command longitude
// @Field: Alt: Command altitude
// @Field: Frame: Frame used for position
// @LoggerMessage: CSRV
// @Description: Servo feedback data
// @Field: TimeUS: Time since system startup
// @Field: Id: Servo number this data relates to
// @Field: Pos: Current servo position
2020-04-07 04:35:05 -03:00
// @Field: Force: Force being applied
2020-04-05 07:50:34 -03:00
// @Field: Speed: Current servo movement speed
// @Field: Pow: Amount of rated power being applied
AP_Logger: add documentation for ACC1,ACC2,ACC3,DMS,GPA,GPA2,GPS2,GYR1,GYR2,GYR3,MAVC,PM
2020-04-03 22:32:14 -03:00
// @LoggerMessage: DMS
// @Description: DataFlash-Over-MAVLink statistics
2020-04-04 21:16:28 -03:00
// @Field: TimeUS: Time since system startup
AP_Logger: add documentation for ACC1,ACC2,ACC3,DMS,GPA,GPA2,GPS2,GYR1,GYR2,GYR3,MAVC,PM
2020-04-03 22:32:14 -03:00
// @Field: N: Current block number
// @Field: Dp: Number of times we rejected a write to the backend
// @Field: RT: Number of blocks sent from the retry queue
// @Field: RS: Number of resends of unacknowledged data made
// @Field: Fa: Average number of blocks on the free list
// @Field: Fmn: Minimum number of blocks on the free list
// @Field: Fmx: Maximum number of blocks on the free list
// @Field: Pa: Average number of blocks on the pending list
// @Field: Pmn: Minimum number of blocks on the pending list
// @Field: Pmx: Maximum number of blocks on the pending list
// @Field: Sa: Average number of blocks on the sent list
// @Field: Smn: Minimum number of blocks on the sent list
// @Field: Smx: Maximum number of blocks on the sent list
AP_Logger: add documentation for more log messages
ERR,DSF,EV,SIM,ORGN,POS,LGR,MON,TSYN,IMU,IMUT
2020-03-21 09:21:59 -03:00
// @LoggerMessage: DSF
// @Description: Onboard logging statistics
// @Field: TimeUS: Time since system startup
// @Field: Dp: Number of times we rejected a write to the backend
// @Field: Blk: Current block number
// @Field: Bytes: Current write offset
// @Field: FMn: Minimum free space in write buffer in last time period
// @Field: FMx: Maximum free space in write buffer in last time period
// @Field: FAv: Average free space in write buffer in last time period
2020-04-06 23:56:14 -03:00
// @LoggerMessage: DSTL
// @Description: Deepstall Landing data
// @Field: TimeUS: Time since system startup
// @Field: Stg: Deepstall landing stage
// @Field: THdg: Target heading
// @Field: Lat: Landing point latitude
// @Field: Lng: Landing point longitude
// @Field: Alt: Landing point altitude
// @Field: XT: Crosstrack error
// @Field: Travel: Expected travel distance vehicle will travel from this point
// @Field: L1I: L1 controller crosstrack integrator value
// @Field: Loiter: wind estimate loiter angle flown
// @Field: Des: Deepstall steering PID desired value
// @Field: P: Deepstall steering PID Proportional response component
// @Field: I: Deepstall steering PID Integral response component
// @Field: D: Deepstall steering PID Derivative response component
AP_Logger: add documentation for more log messages
ERR,DSF,EV,SIM,ORGN,POS,LGR,MON,TSYN,IMU,IMUT
2020-03-21 09:21:59 -03:00
// @LoggerMessage: ERR
// @Description: Specifically coded error messages
// @Field: TimeUS: Time since system startup
2020-04-07 04:35:05 -03:00
// @Field: Subsys: Subsystem in which the error occurred
AP_Logger: add documentation for more log messages
ERR,DSF,EV,SIM,ORGN,POS,LGR,MON,TSYN,IMU,IMUT
2020-03-21 09:21:59 -03:00
// @Field: ECode: Subsystem-specific error code
// @LoggerMessage: EV
// @Description: Specifically coded event messages
// @Field: TimeUS: Time since system startup
// @Field: Id: Event identifier
2019-10-18 00:07:06 -03:00
// @LoggerMessage: FMT
// @Description: Message defining the format of messages in this file
// @URL: https://ardupilot.org/dev/docs/code-overview-adding-a-new-log-message.html
2020-03-20 23:44:24 -03:00
// @Field: Type: unique-to-this-log identifier for message being defined
// @Field: Length: the number of bytes taken up by this message (including all headers)
// @Field: Name: name of the message being defined
// @Field: Format: character string defining the C-storage-type of the fields in this message
// @Field: Columns: the labels of the message being defined
2019-10-18 00:07:06 -03:00
2020-03-25 09:33:03 -03:00
// @LoggerMessage: FMTU
// @Description: Message defining units and multipliers used for fields of other messages
2020-04-07 04:35:05 -03:00
// @Field: TimeUS: Time since system startup
2020-03-25 09:33:03 -03:00
// @Field: FmtType: numeric reference to associated FMT message
// @Field: UnitIds: each character refers to a UNIT message. The unit at an offset corresponds to the field at the same offset in FMT.Format
// @Field: MultIds: each character refers to a MULT message. The multiplier at an offset corresponds to the field at the same offset in FMT.Format
AP_Logger: add documentation for more log messages
ERR,DSF,EV,SIM,ORGN,POS,LGR,MON,TSYN,IMU,IMUT
2020-03-21 09:21:59 -03:00
// @LoggerMessage: LGR
// @Description: Landing gear information
// @Field: TimeUS: Time since system startup
// @Field: LandingGear: Current landing gear state
// @Field: WeightOnWheels: True if there is weight on wheels
2020-11-01 21:46:43 -04:00
// @LoggerMessage: MAG
2020-03-19 23:57:40 -03:00
// @Description: Information received from compasses
2020-04-07 04:35:05 -03:00
// @Field: TimeUS: Time since system startup
2020-11-01 21:46:43 -04:00
// @Field: I: magnetometer sensor instance number
2020-03-19 23:57:40 -03:00
// @Field: MagX: magnetic field strength in body frame
// @Field: MagY: magnetic field strength in body frame
// @Field: MagZ: magnetic field strength in body frame
// @Field: OfsX: magnetic field offset in body frame
// @Field: OfsY: magnetic field offset in body frame
// @Field: OfsZ: magnetic field offset in body frame
2020-11-01 21:46:43 -04:00
// @Field: MOX: motor interference magnetic field offset in body frame
// @Field: MOY: motor interference magnetic field offset in body frame
// @Field: MOZ: motor interference magnetic field offset in body frame
2020-03-19 23:57:40 -03:00
// @Field: Health: true if the compass is considered healthy
// @Field: S: time measurement was taken
2020-03-31 18:37:53 -03:00
// @LoggerMessage: MAV
// @Description: GCS MAVLink link statistics
2020-04-07 04:35:05 -03:00
// @Field: TimeUS: Time since system startup
2020-03-31 18:37:53 -03:00
// @Field: chan: mavlink channel number
// @Field: txp: transmitted packet count
// @Field: rxp: received packet count
// @Field: rxdp: perceived number of packets we never received
// @Field: flags: compact representation of some stage of the channel
// @Field: ss: stream slowdown is the number of ms being added to each message to fit within bandwidth
2020-04-14 19:54:22 -03:00
// @Field: tf: times buffer was full when a message was going to be sent
2020-03-31 18:37:53 -03:00
AP_Logger: add documentation for ACC1,ACC2,ACC3,DMS,GPA,GPA2,GPS2,GYR1,GYR2,GYR3,MAVC,PM
2020-04-03 22:32:14 -03:00
// @LoggerMessage: MAVC
// @Description: MAVLink command we have just executed
2020-04-07 04:35:05 -03:00
// @Field: TimeUS: Time since system startup
AP_Logger: add documentation for ACC1,ACC2,ACC3,DMS,GPA,GPA2,GPS2,GYR1,GYR2,GYR3,MAVC,PM
2020-04-03 22:32:14 -03:00
// @Field: TS: target system for command
// @Field: TC: target component for command
// @Field: Fr: command frame
// @Field: Cmd: mavlink command enum value
// @Field: Cur: current flag from mavlink packet
// @Field: AC: autocontinue flag from mavlink packet
// @Field: P1: first parameter from mavlink packet
// @Field: P2: second parameter from mavlink packet
// @Field: P3: third parameter from mavlink packet
// @Field: P4: fourth parameter from mavlink packet
// @Field: X: X coordinate from mavlink packet
// @Field: Y: Y coordinate from mavlink packet
// @Field: Z: Z coordinate from mavlink packet
// @Field: Res: command result being returned from autopilot
// @Field: WL: true if this command arrived via a COMMAND_LONG rather than COMMAND_INT
2020-03-19 23:57:40 -03:00
// @LoggerMessage: MODE
// @Description: vehicle control mode information
2020-04-07 04:35:05 -03:00
// @Field: TimeUS: Time since system startup
2020-03-19 23:57:40 -03:00
// @Field: Mode: vehicle-specific mode number
// @Field: ModeNum: alias for Mode
// @Field: Rsn: reason for entering this mode; enumeration value
2020-03-17 22:13:16 -03:00
AP_Logger: add documentation for more log messages
ERR,DSF,EV,SIM,ORGN,POS,LGR,MON,TSYN,IMU,IMUT
2020-03-21 09:21:59 -03:00
// @LoggerMessage: MON
// @Description: Main loop stuck data
2020-04-07 04:35:05 -03:00
// @Field: TimeUS: Time since system startup
AP_Logger: add documentation for more log messages
ERR,DSF,EV,SIM,ORGN,POS,LGR,MON,TSYN,IMU,IMUT
2020-03-21 09:21:59 -03:00
// @Field: LDelay: Time main loop has been stuck for
// @Field: Task: Current scheduler task number
// @Field: IErr: Internal error mask; which internal errors have been detected
// @Field: IErrCnt: Internal error count; how many internal errors have been detected
2020-04-29 21:40:46 -03:00
// @Field: IErrLn: Line on which internal error ocurred
AP_Logger: add documentation for more log messages
ERR,DSF,EV,SIM,ORGN,POS,LGR,MON,TSYN,IMU,IMUT
2020-03-21 09:21:59 -03:00
// @Field: MavMsg: Id of the last mavlink message processed
// @Field: MavCmd: Id of the last mavlink command processed
// @Field: SemLine: Line number of semaphore most recently taken
// @Field: SPICnt: Number of SPI transactions processed
// @Field: I2CCnt: Number of i2c transactions processed
2020-04-02 20:07:46 -03:00
// @LoggerMessage: MSG
// @Description: Textual messages
2020-04-07 04:35:05 -03:00
// @Field: TimeUS: Time since system startup
2020-04-02 20:07:46 -03:00
// @Field: Message: message text
2020-03-25 09:33:03 -03:00
// @LoggerMessage: MULT
// @Description: Message mapping from single character to numeric multiplier
2020-04-07 04:35:05 -03:00
// @Field: TimeUS: Time since system startup
2020-03-25 09:33:03 -03:00
// @Field: Id: character referenced by FMTU
// @Field: Mult: numeric multiplier
2020-04-05 07:50:34 -03:00
// @LoggerMessage: OF
// @Description: Optical flow sensor data
// @Field: TimeUS: Time since system startup
// @Field: Qual: Estimated sensor data quality
// @Field: flowX: Sensor flow rate, X-axis
// @Field: flowY: Sensor flow rate,Y-axis
// @Field: bodyX: derived velocity, X-axis
// @Field: bodyY: derived velocity, Y-axis
2020-03-31 18:37:53 -03:00
// @LoggerMessage: PARM
// @Description: parameter value
2020-04-07 04:35:05 -03:00
// @Field: TimeUS: Time since system startup
2020-03-31 18:37:53 -03:00
// @Field: Name: parameter name
2020-12-17 08:40:55 -04:00
// @Field: Value: parameter value
2020-03-31 18:37:53 -03:00
2020-03-19 23:57:40 -03:00
// @LoggerMessage: PIDR,PIDP,PIDY,PIDA,PIDS
2020-07-21 12:08:01 -03:00
// @Description: Proportional/Integral/Derivative gain values for Roll/Pitch/Yaw/Altitude/Steering
2020-04-07 04:35:05 -03:00
// @Field: TimeUS: Time since system startup
2020-03-19 23:57:40 -03:00
// @Field: Tar: desired value
// @Field: Act: achieved value
// @Field: Err: error between target and achieved
2020-03-21 10:03:33 -03:00
// @Field: P: proportional part of PID
2020-03-19 23:57:40 -03:00
// @Field: I: integral part of PID
2020-03-21 10:03:33 -03:00
// @Field: D: derivative part of PID
2020-03-19 23:57:40 -03:00
// @Field: FF: controller feed-forward portion of response
2020-05-10 04:16:23 -03:00
// @Field: Dmod: scaler applied to D gain to reduce limit cycling
2021-04-04 06:49:09 -03:00
// @Field: SRate: slew rate used in slew limiter
// @Field: Limit: 1 if I term is limited due to output saturation
2020-03-19 23:57:40 -03:00
AP_Logger: add documentation for ACC1,ACC2,ACC3,DMS,GPA,GPA2,GPS2,GYR1,GYR2,GYR3,MAVC,PM
2020-04-03 22:32:14 -03:00
// @LoggerMessage: PM
// @Description: autopilot system performance and general data dumping ground
2020-04-07 04:35:05 -03:00
// @Field: TimeUS: Time since system startup
AP_Logger: add documentation for ACC1,ACC2,ACC3,DMS,GPA,GPA2,GPS2,GYR1,GYR2,GYR3,MAVC,PM
2020-04-03 22:32:14 -03:00
// @Field: NLon: Number of long loops detected
// @Field: NLoop: Number of measurement loops for this message
// @Field: MaxT: Maximum loop time
// @Field: Mem: Free memory available
// @Field: Load: System processor load
// @Field: IntE: Internal error mask; which internal errors have been detected
2020-10-09 15:55:03 -03:00
// @Field: ErrL: Internal error line number; last line number on which a internal error was detected
// @Field: ErrC: Internal error count; how many internal errors have been detected
AP_Logger: add documentation for ACC1,ACC2,ACC3,DMS,GPA,GPA2,GPS2,GYR1,GYR2,GYR3,MAVC,PM
2020-04-03 22:32:14 -03:00
// @Field: SPIC: Number of SPI transactions processed
// @Field: I2CC: Number of i2c transactions processed
// @Field: I2CI: Number of i2c interrupts serviced
2020-10-09 15:55:03 -03:00
// @Field: Ex: number of microseconds being added to each loop to address scheduler overruns
AP_Logger: add documentation for ACC1,ACC2,ACC3,DMS,GPA,GPA2,GPS2,GYR1,GYR2,GYR3,MAVC,PM
2020-04-03 22:32:14 -03:00
2020-04-05 07:50:34 -03:00
// @LoggerMessage: POWR
// @Description: System power information
// @Field: TimeUS: Time since system startup
// @Field: Vcc: Flight board voltage
// @Field: VServo: Servo rail voltage
// @Field: Flags: System power flags
2020-07-19 21:34:43 -03:00
// @Field: AccFlags: Accumulated System power flags; all flags which have ever been set
2020-04-05 07:50:34 -03:00
// @Field: Safety: Hardware Safety Switch status
2020-04-12 04:19:56 -03:00
// @LoggerMessage: PRX
2021-02-12 04:31:30 -04:00
// @Description: Proximity Filtered sensor data
2020-04-12 04:19:56 -03:00
// @Field: TimeUS: Time since system startup
2021-02-12 04:31:30 -04:00
// @Field: Layer: Pitch(instance) at which the obstacle is at. 0th layer {-75,-45} degrees. 1st layer {-45,-15} degrees. 2nd layer {-15, 15} degrees. 3rd layer {15, 45} degrees. 4th layer {45,75} degrees. Minimum distance in each layer will be logged.
// @Field: He: True if proximity sensor is healthy
2020-04-12 04:19:56 -03:00
// @Field: D0: Nearest object in sector surrounding 0-degrees
// @Field: D45: Nearest object in sector surrounding 45-degrees
// @Field: D90: Nearest object in sector surrounding 90-degrees
// @Field: D135: Nearest object in sector surrounding 135-degrees
// @Field: D180: Nearest object in sector surrounding 180-degrees
// @Field: D225: Nearest object in sector surrounding 225-degrees
// @Field: D270: Nearest object in sector surrounding 270-degrees
// @Field: D315: Nearest object in sector surrounding 315-degrees
// @Field: DUp: Nearest object in upwards direction
// @Field: CAn: Angle to closest object
// @Field: CDis: Distance to closest object
2021-02-12 04:31:30 -04:00
// @LoggerMessage: PRXR
// @Description: Proximity Raw sensor data
// @Field: TimeUS: Time since system startup
// @Field: Layer: Pitch(instance) at which the obstacle is at. 0th layer {-75,-45} degrees. 1st layer {-45,-15} degrees. 2nd layer {-15, 15} degrees. 3rd layer {15, 45} degrees. 4th layer {45,75} degrees. Minimum distance in each layer will be logged.
// @Field: D0: Nearest object in sector surrounding 0-degrees
// @Field: D45: Nearest object in sector surrounding 45-degrees
// @Field: D90: Nearest object in sector surrounding 90-degrees
// @Field: D135: Nearest object in sector surrounding 135-degrees
// @Field: D180: Nearest object in sector surrounding 180-degrees
// @Field: D225: Nearest object in sector surrounding 225-degrees
// @Field: D270: Nearest object in sector surrounding 270-degrees
// @Field: D315: Nearest object in sector surrounding 315-degrees
2020-04-02 20:07:46 -03:00
// @LoggerMessage: RAD
// @Description: Telemetry radio statistics
// @Field: TimeUS: Time since system startup
// @Field: RSSI: RSSI
// @Field: RemRSSI: RSSI reported from remote radio
// @Field: TxBuf: number of bytes in radio ready to be sent
// @Field: Noise: local noise floor
// @Field: RemNoise: local noise floor reported from remote radio
// @Field: RxErrors: damaged packet count
// @Field: Fixed: fixed damaged packet count
// @LoggerMessage: RALY
// @Description: Rally point information
// @Field: TimeUS: Time since system startup
// @Field: Tot: total number of rally points onboard
// @Field: Seq: this rally point's sequence number
// @Field: Lat: latitude of rally point
// @Field: Lng: longitude of rally point
// @Field: Alt: altitude of rally point
2020-03-19 23:57:40 -03:00
// @LoggerMessage: RCIN
// @Description: RC input channels to vehicle
2020-04-07 04:35:05 -03:00
// @Field: TimeUS: Time since system startup
2020-03-19 23:57:40 -03:00
// @Field: C1: channel 1 input
// @Field: C2: channel 2 input
// @Field: C3: channel 3 input
// @Field: C4: channel 4 input
// @Field: C5: channel 5 input
// @Field: C6: channel 6 input
// @Field: C7: channel 7 input
// @Field: C8: channel 8 input
// @Field: C9: channel 9 input
// @Field: C10: channel 10 input
// @Field: C11: channel 11 input
// @Field: C12: channel 12 input
// @Field: C13: channel 13 input
// @Field: C14: channel 14 input
// @LoggerMessage: RCOU
// @Description: Servo channel output values
2020-04-07 04:35:05 -03:00
// @Field: TimeUS: Time since system startup
2020-03-19 23:57:40 -03:00
// @Field: C1: channel 1 output
// @Field: C2: channel 2 output
// @Field: C3: channel 3 output
// @Field: C4: channel 4 output
// @Field: C5: channel 5 output
// @Field: C6: channel 6 output
// @Field: C7: channel 7 output
// @Field: C8: channel 8 output
// @Field: C9: channel 9 output
// @Field: C10: channel 10 output
// @Field: C11: channel 11 output
// @Field: C12: channel 12 output
// @Field: C13: channel 13 output
// @Field: C14: channel 14 output
2020-04-02 20:07:46 -03:00
// @LoggerMessage: RFND
// @Description: Rangefinder sensor information
// @Field: TimeUS: Time since system startup
// @Field: Instance: rangefinder instance number this data is from
// @Field: Dist: Reported distance from sensor
// @Field: Stat: Sensor state
// @Field: Orient: Sensor orientation
// @LoggerMessage: RPM
// @Description: Data from RPM sensors
// @Field: TimeUS: Time since system startup
// @Field: rpm1: First sensor's data
// @Field: rpm2: Second sensor's data
// @LoggerMessage: RSSI
// @Description: Received Signal Strength Indicator for RC receiver
// @Field: TimeUS: Time since system startup
// @Field: RXRSSI: RSSI
AP_Logger: add documentation for more log messages
ERR,DSF,EV,SIM,ORGN,POS,LGR,MON,TSYN,IMU,IMUT
2020-03-21 09:21:59 -03:00
// @LoggerMessage: SIM
// @Description: SITL simulator state
// @Field: TimeUS: Time since system startup
// @Field: Roll: Simulated roll
// @Field: Pitch: Simulated pitch
// @Field: Yaw: Simulated yaw
// @Field: Alt: Simulated altitude
// @Field: Lat: Simulated latitude
// @Field: Lng: Simulated longitude
// @Field: Q1: Attitude quaternion component 1
// @Field: Q2: Attitude quaternion component 2
// @Field: Q3: Attitude quaternion component 3
// @Field: Q4: Attitude quaternion component 4
2020-03-25 09:33:03 -03:00
// @LoggerMessage: SRTL
// @Description: SmartRTL statistics
2020-04-07 04:35:05 -03:00
// @Field: TimeUS: Time since system startup
2020-03-25 09:33:03 -03:00
// @Field: Active: true if SmartRTL could be used right now
// @Field: NumPts: number of points currently in use
// @Field: MaxPts: maximum number of points that could be used
// @Field: Action: most recent internal action taken by SRTL library
// @Field: N: point associated with most recent action (North component)
// @Field: E: point associated with most recent action (East component)
// @Field: D: point associated with most recent action (Down component)
2020-04-05 07:50:34 -03:00
// @LoggerMessage: TERR
// @Description: Terrain database infomration
// @Field: TimeUS: Time since system startup
// @Field: Status: Terrain database status
// @Field: Lat: Current vehicle latitude
// @Field: Lng: Current vehicle longitude
// @Field: Spacing: terrain Tile spacing
// @Field: TerrH: current Terrain height
// @Field: CHeight: Vehicle height above terrain
// @Field: Pending: Number of tile requests outstanding
// @Field: Loaded: Number of tiles in memory
AP_Logger: add documentation for more log messages
ERR,DSF,EV,SIM,ORGN,POS,LGR,MON,TSYN,IMU,IMUT
2020-03-21 09:21:59 -03:00
// @LoggerMessage: TSYN
// @Description: Time synchronisation response information
// @Field: TimeUS: Time since system startup
// @Field: SysID: system ID this data is for
// @Field: RTT: round trip time for this system
2020-03-25 09:33:03 -03:00
// @LoggerMessage: UNIT
// @Description: Message mapping from single character to SI unit
2020-04-07 04:35:05 -03:00
// @Field: TimeUS: Time since system startup
2020-03-25 09:33:03 -03:00
// @Field: Id: character referenced by FMTU
// @Field: Label: Unit - SI where available
2020-04-12 04:19:56 -03:00
// @LoggerMessage: WENC
// @Description: Wheel encoder measurements
// @Field: TimeUS: Time since system startup
// @Field: Dist0: First wheel distance travelled
// @Field: Qual0: Quality measurement of Dist0
// @Field: Dist1: Second wheel distance travelled
// @Field: Qual1: Quality measurement of Dist1
2020-07-24 02:59:41 -03:00
// @LoggerMessage: WINC
// @Description: Winch
// @Field: TimeUS: Time since system startup
// @Field: Heal: Healthy
// @Field: ThEnd: Reached end of thread
// @Field: Mov: Motor is moving
// @Field: Clut: Clutch is engaged (motor can move freely)
// @Field: Mode: 0 is Relaxed, 1 is Position Control, 2 is Rate Control
// @Field: DLen: Desired Length
// @Field: Len: Estimated Length
// @Field: DRate: Desired Rate
// @Field: Tens: Tension on line
// @Field: Vcc: Voltage to Motor
// @Field: Temp: Motor temperature
2020-09-09 04:16:39 -03:00
// @LoggerMessage: PSC
// @Description: Position Control data
// @Field: TimeUS: Time since system startup
// @Field: TPX: Target position relative to origin, X-axis
// @Field: TPY: Target position relative to origin, Y-axis
// @Field: PX: Position relative to origin, X-axis
// @Field: PY: Position relative to origin, Y-axis
// @Field: TVX: Target velocity, X-axis
// @Field: TVY: Target velocity, Y-axis
// @Field: VX: Velocity, X-axis
// @Field: VY: Velocity, Y-axis
// @Field: TAX: Target acceleration, X-axis
// @Field: TAY: Target acceleration, Y-axis
// @Field: AX: Acceleration, X-axis
// @Field: AY: Acceleration, Y-axis
2021-01-29 00:42:26 -04:00
// @LoggerMessage: PSCZ
// @Description: Position Control Z-axis
// @Field: TimeUS: Time since system startup
// @Field: TPZ: Target position above EKF origin
// @Field: PZ: Position above EKF origin
// @Field: DVZ: Desired velocity Z-axis
// @Field: TVZ: Target velocity Z-axis
// @Field: VZ: Velocity Z-axis
// @Field: DAZ: Desired acceleration Z-axis
// @Field: TAZ: Target acceleration Z-axis
// @Field: AZ: Acceleration Z-axis
// @Field: ThO: Throttle output
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-- " } , \
2021-02-09 19:08:38 -04:00
LOG_STRUCTURE_FROM_GPS \
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-------------- " } , \
2020-08-19 05:56:50 -03:00
{ LOG_RCIN2_MSG , sizeof ( log_RCIN2 ) , \
2021-05-15 00:45:43 -03:00
" RCI2 " , " QHHH " , " TimeUS,C15,C16,OMask " , " sYY- " , " 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- " } , \
2021-02-02 00:08:50 -04:00
LOG_STRUCTURE_FROM_BARO \
2021-04-12 07:40:50 -03:00
LOG_STRUCTURE_FROM_PRECLAND \
2015-11-05 19:50:54 -04:00
{ LOG_POWR_MSG , sizeof ( log_POWR ) , \
2020-07-19 21:34:43 -03:00
" POWR " , " QffHHB " , " TimeUS,Vcc,VServo,Flags,AccFlags,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------- " } , \
2021-01-22 15:51:48 -04:00
LOG_STRUCTURE_FROM_CAMERA \
2020-11-18 18:52:49 -04:00
{ LOG_ARSP_MSG , sizeof ( log_ARSP ) , " ARSP " , " QBffcffBBfB " , " TimeUS,I,Airspeed,DiffPress,Temp,RawPress,Offset,U,H,Hfp,Pri " , " s#nPOPP---- " , " F-00B00---- " } , \
2021-01-11 21:43:14 -04:00
LOG_STRUCTURE_FROM_BATTMONITOR \
2020-11-01 21:46:43 -04:00
{ LOG_MAG_MSG , sizeof ( log_MAG ) , \
" MAG " , " QBhhhhhhhhhBI " , " TimeUS,I,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOX,MOY,MOZ,Health,S " , " s#GGGGGGGGG-s " , " F-CCCCCCCCC-F " } , \
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 ) , \
2020-04-03 22:37:36 -03:00
" DMS " , " QIIIIBBBBBBBBB " , " TimeUS,N,Dp,RT,RS,Fa,Fmn,Fmx,Pa,Pmn,Pmx,Sa,Smn,Smx " , " s------------- " , " F------------- " } , \
2017-04-18 11:43:03 -03:00
{ LOG_BEACON_MSG , sizeof ( log_Beacon ) , \
2021-01-06 04:29:15 -04:00
" BCN " , " QBBfffffff " , " TimeUS,Health,Cnt,D0,D1,D2,D3,PosX,PosY,PosZ " , " s--mmmmmmm " , " F--0000000 " } , \
2017-07-14 14:00:13 -03:00
{ LOG_PROXIMITY_MSG , sizeof ( log_Proximity ) , \
2021-02-12 04:31:30 -04:00
" PRX " , " QBBfffffffffff " , " TimeUS,Layer,He,D0,D45,D90,D135,D180,D225,D270,D315,DUp,CAn,CDis " , " s#-mmmmmmmmmhm " , " F--00000000000 " } , \
{ LOG_RAW_PROXIMITY_MSG , sizeof ( log_Proximity_raw ) , \
" PRXR " , " QBffffffff " , " TimeUS,Layer,D0,D45,D90,D135,D180,D225,D270,D315 " , " s#mmmmmmmm " , " F-00000000 " } , \
2017-11-15 23:20:17 -04:00
{ LOG_PERFORMANCE_MSG , sizeof ( log_Performance ) , \
2020-10-09 15:55:03 -03:00
" PM " , " QHHIIHHIIIIII " , " TimeUS,NLon,NLoop,MaxT,Mem,Load,ErrL,IntE,ErrC,SPIC,I2CC,I2CI,Ex " , " 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 " } , \
2021-01-22 03:24:54 -04:00
LOG_STRUCTURE_FROM_AVOIDANCE \
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_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-- " } , \
2021-03-17 05:35:40 -03:00
LOG_STRUCTURE_FROM_ESC_TELEM \
2020-01-04 00:25:55 -04:00
{ LOG_CSRV_MSG , sizeof ( log_CSRV ) , \
" CSRV " , " QBfffB " , " TimeUS,Id,Pos,Force,Speed,Pow " , " s#---% " , " F-0000 " } , \
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 } , \
2020-01-04 02:17:32 -04:00
{ LOG_PIDN_MSG , sizeof ( log_PID ) , \
" PIDN " , PID_FMT , PID_LABELS , PID_UNITS , PID_MULTS } , \
{ LOG_PIDE_MSG , sizeof ( log_PID ) , \
" PIDE " , 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-------- " } , \
2021-02-09 15:05:03 -04:00
LOG_STRUCTURE_FROM_INERTIALSENSOR \
2020-11-05 19:26:16 -04:00
LOG_STRUCTURE_FROM_DAL \
LOG_STRUCTURE_FROM_NAVEKF2 \
LOG_STRUCTURE_FROM_NAVEKF3 \
2021-02-17 18:34:13 -04:00
LOG_STRUCTURE_FROM_NAVEKF \
2021-01-08 23:45:38 -04:00
LOG_STRUCTURE_FROM_AHRS \
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-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 ) , \
2020-04-14 19:54:22 -03:00
" MAV " , " QBHHHBHH " , " TimeUS,chan,txp,rxp,rxdp,flags,ss,tf " , " s#----s- " , " F-000-C- " } , \
2021-02-02 22:12:58 -04:00
LOG_STRUCTURE_FROM_VISUALODOM \
2018-09-02 09:27:58 -03:00
{ LOG_OPTFLOW_MSG , sizeof ( log_Optflow ) , \
2020-04-05 20:13:20 -03:00
" OF " , " QBffff " , " TimeUS,Qual,flowX,flowY,bodyX,bodyY " , " s-EEnn " , " F-0000 " } , \
2019-02-05 01:00:28 -04:00
{ 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 ) , \
2019-12-09 05:10:39 -04:00
" ADSB " , " QIiiiHHhH " , " TimeUS,ICAO_address,Lat,Lng,Alt,Heading,Hor_vel,Ver_vel,Squark " , " s-DUmhnn- " , " F-GGCBCC- " } , \
{ LOG_EVENT_MSG , sizeof ( log_Event ) , \
" EV " , " QB " , " TimeUS,Id " , " s- " , " F- " } , \
{ LOG_ARM_DISARM_MSG , sizeof ( log_Arm_Disarm ) , \
2020-02-11 21:25:28 -04:00
" ARM " , " QBIBB " , " TimeUS,ArmState,ArmChecks,Forced,Method " , " s---- " , " F---- " } , \
2019-12-09 05:10:39 -04:00
{ LOG_ERROR_MSG , sizeof ( log_Error ) , \
2020-07-24 02:59:41 -03:00
" ERR " , " QBB " , " TimeUS,Subsys,ECode " , " s-- " , " F-- " } , \
{ LOG_WINCH_MSG , sizeof ( log_Winch ) , \
2020-09-09 04:16:39 -03:00
" WINC " , " QBBBBBfffHfb " , " TimeUS,Heal,ThEnd,Mov,Clut,Mode,DLen,Len,DRate,Tens,Vcc,Temp " , " s-----mmn?vO " , " F-----000000 " } , \
{ LOG_PSC_MSG , sizeof ( log_PSC ) , \
2021-01-29 00:42:26 -04:00
" PSC " , " Qffffffffffff " , " TimeUS,TPX,TPY,PX,PY,TVX,TVY,VX,VY,TAX,TAY,AX,AY " , " smmmmnnnnoooo " , " F000000000000 " } , \
{ LOG_PSCZ_MSG , sizeof ( log_PSCZ ) , \
" PSCZ " , " Qfffffffff " , " TimeUS,TPZ,PZ,DVZ,TVZ,VZ,DAZ,TAZ,AZ,ThO " , " smmnnnooo% " , " F000000002 " }
2015-11-05 19:50:54 -04:00
2020-05-20 23:53:46 -03:00
// @LoggerMessage: SBPH
// @Description: Swift Health Data
// @Field: TimeUS: Time since system startup
// @Field: CrcError: Number of packet CRC errors on serial connection
// @Field: LastInject: Timestamp of last raw data injection to GPS
// @Field: IARhyp: Current number of integer ambiguity hypotheses
// @LoggerMessage: SBRH
// @Description: Swift Raw Message Data
// @Field: TimeUS: Time since system startup
// @Field: msg_flag: Swift message type
// @Field: 1: Sender ID
// @Field: 2: index; always 1
// @Field: 3: pages; number of pages received
// @Field: 4: msg length; number of bytes received
// @Field: 5: unused; always zero
// @Field: 6: data received from device
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?????????????? " } , \
2017-06-29 11:17:10 -03:00
{ LOG_MSG_SBPEVENT , sizeof ( log_SbpEvent ) , \
2019-12-09 05:10:39 -04:00
" SBRE " , " QHIiBB " , " TimeUS,GWk,GMS,ns_residual,level,quality " , " s????? " , " F????? " }
2019-03-24 22:04:59 -03:00
2019-12-09 05:10:39 -04:00
# define LOG_COMMON_STRUCTURES LOG_BASE_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 {
2020-12-03 06:29:50 -04:00
LOG_PARAMETER_MSG = 64 ,
2020-12-03 06:30:24 -04:00
LOG_IDS_FROM_NAVEKF2 ,
LOG_IDS_FROM_NAVEKF3 ,
2015-11-05 19:50:54 -04:00
LOG_MESSAGE_MSG ,
LOG_RCIN_MSG ,
2020-08-19 05:56:50 -03:00
LOG_RCIN2_MSG ,
2015-11-05 19:50:54 -04:00
LOG_RCOUT_MSG ,
LOG_RSSI_MSG ,
2021-02-02 00:08:50 -04:00
LOG_IDS_FROM_BARO ,
2015-11-05 19:50:54 -04:00
LOG_POWR_MSG ,
2021-01-08 23:45:38 -04:00
LOG_IDS_FROM_AHRS ,
2015-11-05 19:50:54 -04:00
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 ,
2021-04-12 01:43:11 -03:00
LOG_ATRP_MSG ,
2021-01-22 15:51:48 -04:00
LOG_IDS_FROM_CAMERA ,
2015-11-05 19:50:54 -04:00
LOG_TERRAIN_MSG ,
2020-01-04 00:25:55 -04:00
LOG_CSRV_MSG ,
2015-11-05 19:50:54 -04:00
LOG_ARSP_MSG ,
2021-03-17 05:35:40 -03:00
LOG_IDS_FROM_ESC_TELEM ,
2021-01-11 21:43:14 -04:00
LOG_IDS_FROM_BATTMONITOR ,
2020-11-01 21:46:43 -04:00
LOG_MAG_MSG ,
2020-01-15 04:00:49 -04:00
2021-02-09 19:08:38 -04:00
LOG_IDS_FROM_GPS ,
// LOG_MODE_MSG is used as a check for duplicates. Do not add between this and LOG_FORMAT_MSG
LOG_MODE_MSG ,
2020-01-15 04:00:49 -04:00
LOG_FORMAT_MSG = 128 , // this must remain #128
2020-11-05 19:26:16 -04:00
LOG_IDS_FROM_DAL ,
2021-02-09 15:05:03 -04:00
LOG_IDS_FROM_INERTIALSENSOR ,
2020-11-05 19:26:16 -04:00
2015-11-05 19:50:54 -04:00
LOG_PIDR_MSG ,
LOG_PIDP_MSG ,
LOG_PIDY_MSG ,
LOG_PIDA_MSG ,
LOG_PIDS_MSG ,
2020-01-04 02:17:32 -04:00
LOG_PIDN_MSG ,
LOG_PIDE_MSG ,
2017-10-12 19:26:43 -03:00
LOG_DSTL_MSG ,
2015-11-05 19:50:54 -04:00
LOG_RPM_MSG ,
LOG_RFND_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 ,
2015-11-09 18:10:46 -04:00
2016-07-03 23:14:26 -03:00
LOG_RALLY_MSG ,
2021-02-02 22:12:58 -04:00
LOG_IDS_FROM_VISUALODOM ,
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-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 ,
2021-01-22 03:24:54 -04:00
LOG_IDS_FROM_AVOIDANCE ,
2020-07-24 02:59:41 -03:00
LOG_WINCH_MSG ,
2020-09-09 04:16:39 -03:00
LOG_PSC_MSG ,
2021-01-29 00:42:26 -04:00
LOG_PSCZ_MSG ,
2021-02-12 04:31:30 -04:00
LOG_RAW_PROXIMITY_MSG ,
2021-04-12 07:40:50 -03:00
LOG_IDS_FROM_PRECLAND ,
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 " ) ;
2021-02-09 19:08:38 -04:00
static_assert ( LOG_MODE_MSG < 128 , " Duplicate message format IDs " ) ;
2017-11-15 23:20:17 -04:00
2015-11-05 19:50:54 -04:00
enum LogOriginType {
ekf_origin = 0 ,
ahrs_home = 1
} ;