forked from ArduPilot/ardupilot
/
LogStructure.h
1436 lines (1319 loc) · 46.9 KB
/
LogStructure.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
#pragma once
#include <AP_Common/AP_Common.h>
// if you add any new types, units or multipliers, please update README.md
/*
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
*/
struct UnitStructure {
const char ID;
const char *unit;
};
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"
// Please keep the names consistent with Tools/autotest/param_metadata/param.py:33
const struct UnitStructure log_Units[] = {
{ '-', "" }, // no units e.g. Pi, or a string
{ '?', "UNKNOWN" }, // Units which haven't been worked out yet....
{ 'A', "A" }, // Ampere
{ 'a', "Ah" }, // Ampere hours
{ '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
{ 'J', "W.s" }, // Joule (Watt second)
{ '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
{ '%', "%" }, // percent
{ '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
{ 'W', "Watt" }, // Watt
{ 'X', "W.h" }, // Watt hour
{ 'y', "l/s" }, // litres per second
{ 'Y', "us" }, // pulse width modulation in microseconds
{ 'z', "Hz" }, // Hertz
{ '#', "instance" } // (e.g.)Sensor instance number
};
// 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[] = {
{ '-', 0 }, // no multiplier e.g. a string
{ '?', 1 }, // multipliers which haven't been worked out yet....
// <leave a gap here, just in case....>
{ '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 },
{ 'I', 1e-9 },
// <leave a gap here, just in case....>
{ '!', 3.6 }, // (ampere*second => milliampere*hour) and (km/h => m/s)
{ '/', 3600 }, // (ampere*second => ampere*hour)
};
/*
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
#include <AP_Beacon/LogStructure.h>
#include <AP_DAL/LogStructure.h>
#include <AP_NavEKF2/LogStructure.h>
#include <AP_NavEKF3/LogStructure.h>
#include <AP_GPS/LogStructure.h>
#include <AP_NavEKF/LogStructure.h>
#include <AP_BattMonitor/LogStructure.h>
#include <AP_InertialSensor/LogStructure.h>
#include <AP_AHRS/LogStructure.h>
#include <AP_Camera/LogStructure.h>
#include <AP_Mount/LogStructure.h>
#include <AP_Baro/LogStructure.h>
#include <AP_VisualOdom/LogStructure.h>
#include <AC_PrecLand/LogStructure.h>
#include <AP_Proximity/LogStructure.h>
#include <AC_Avoidance/LogStructure.h>
#include <AP_ESC_Telem/LogStructure.h>
#include <AP_AIS/LogStructure.h>
#include <AP_HAL_ChibiOS/LogStructure.h>
#include <AP_RPM/LogStructure.h>
#include <AC_Fence/LogStructure.h>
#include <AP_Landing/LogStructure.h>
// structure used to define logging format
// It is packed on ChibiOS to save flash space; however, this causes problems
// when building the SITL on an Apple M1 CPU (and is also slower) so we do not
// pack it by default
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
struct PACKED LogStructure {
#else
struct LogStructure {
#endif
uint8_t msg_type;
uint8_t msg_len;
const char *name;
const char *format;
const char *labels;
const char *units;
const char *multipliers;
bool streaming; // can be rate limited
};
// 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];
};
struct PACKED log_Parameter {
LOG_PACKET_HEADER;
uint64_t time_us;
char name[16];
float value;
float default_value;
};
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;
};
struct PACKED log_Event {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t id;
};
struct PACKED log_Error {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t sub_system;
uint8_t error_code;
};
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;
};
struct PACKED log_RCI2 {
LOG_PACKET_HEADER;
uint64_t time_us;
uint16_t chan15;
uint16_t chan16;
uint16_t override_mask;
uint8_t flags;
};
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;
uint16_t chan13;
uint16_t chan14;
};
struct PACKED log_RCOUT2 {
LOG_PACKET_HEADER;
uint64_t time_us;
uint16_t chan15;
uint16_t chan16;
uint16_t chan17;
uint16_t chan18;
};
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;
uint8_t flags;
uint16_t stream_slowdown_ms;
uint16_t times_full;
};
struct PACKED log_RSSI {
LOG_PACKET_HEADER;
uint64_t time_us;
float RXRSSI;
float RXLQ;
};
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;
};
struct PACKED log_POWR {
LOG_PACKET_HEADER;
uint64_t time_us;
float Vcc;
float Vservo;
uint16_t flags;
uint16_t accumulated_flags;
uint8_t safety_and_arm;
};
struct PACKED log_MCU {
LOG_PACKET_HEADER;
uint64_t time_us;
float MCU_temp;
float MCU_voltage;
float MCU_voltage_min;
float MCU_voltage_max;
};
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;
int32_t latitude;
int32_t longitude;
float altitude;
uint8_t frame;
};
struct PACKED log_MAVLink_Command {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t target_system;
uint8_t target_component;
uint8_t source_system;
uint8_t source_component;
uint8_t frame;
uint16_t command;
float param1;
float param2;
float param3;
float param4;
int32_t x;
int32_t y;
float z;
uint8_t result;
bool was_command_long;
};
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;
float target;
float actual;
float error;
float P;
float I;
float D;
float FF;
float DFF;
float Dmod;
float slew_rate;
uint8_t flags;
};
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;
};
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;
};
struct PACKED log_MAG {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t instance;
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;
uint32_t SUS;
};
struct PACKED log_Mode {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t mode;
uint8_t mode_num;
uint8_t mode_reason;
};
/*
rangefinder - support for 4 sensors
*/
struct PACKED log_RFND {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t instance;
uint16_t dist;
uint8_t status;
uint8_t orient;
int8_t quality;
};
/*
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;
float reference_offset;
};
struct PACKED log_CSRV {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t id;
float position;
float force;
float speed;
uint8_t power_pct;
float pos_cmd;
float voltage;
float current;
float mot_temp;
float pcb_temp;
uint8_t error;
};
struct PACKED log_ARSP {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t instance;
float airspeed;
float diffpressure;
int16_t temperature;
float rawpressure;
float offset;
bool use;
bool healthy;
float health_prob;
float test_ratio;
uint8_t primary;
};
struct PACKED log_MAV_Stats {
LOG_PACKET_HEADER;
uint64_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;
};
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;
uint8_t flags;
};
struct PACKED log_Performance {
LOG_PACKET_HEADER;
uint64_t time_us;
uint16_t loop_rate;
uint16_t num_long_running;
uint16_t num_loops;
uint32_t max_time;
uint32_t mem_avail;
uint16_t load;
uint16_t internal_error_last_line;
uint32_t internal_errors;
uint32_t internal_error_count;
uint32_t spi_count;
uint32_t i2c_count;
uint32_t i2c_isr_count;
uint32_t extra_loop_us;
};
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;
};
struct PACKED log_Arm_Disarm {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t arm_state;
uint32_t arm_checks;
uint8_t forced;
uint8_t method;
};
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;
};
// position controller per-axis logging
struct PACKED log_PSCx {
LOG_PACKET_HEADER;
uint64_t time_us;
float pos_target;
float pos;
float vel_desired;
float vel_target;
float vel;
float accel_desired;
float accel_target;
float accel;
};
// thread stack usage
struct PACKED log_STAK {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t thread_id;
uint8_t priority;
uint16_t stack_total;
uint16_t stack_free;
char name[16];
};
struct PACKED log_File {
LOG_PACKET_HEADER;
char filename[16];
uint32_t offset;
uint8_t length;
char data[64];
};
struct PACKED log_Scripting {
LOG_PACKET_HEADER;
uint64_t time_us;
char name[16];
uint32_t run_time;
int32_t total_mem;
int32_t run_mem;
};
struct PACKED log_MotBatt {
LOG_PACKET_HEADER;
uint64_t time_us;
float lift_max;
float bat_volt;
float th_limit;
float th_average_max;
float th_out;
uint8_t mot_fail_flags;
};
struct PACKED log_VER {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t board_type;
uint16_t board_subtype;
uint8_t major;
uint8_t minor;
uint8_t patch;
uint8_t fw_type;
uint32_t git_hash;
char fw_string[64];
uint16_t _APJ_BOARD_ID;
uint8_t build_type;
};
// 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
#define PID_LABELS "TimeUS,Tar,Act,Err,P,I,D,FF,DFF,Dmod,SRate,Flags"
#define PID_FMT "QffffffffffB"
#define PID_UNITS "s-----------"
#define PID_MULTS "F-----------"
#define PIDx_FMT "Qffffffff"
#define PIDx_UNITS "smmnnnooo"
#define PIDx_MULTS "F00000000"
// @LoggerMessage: ADSB
// @Description: Automatic Dependent 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
// @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
// @FieldBitmaskEnum: ArmChecks: AP_Arming::ArmingChecks
// @Field: Forced: true if arm/disarm was forced
// @Field: Method: method used for arming
// @FieldValueEnum: Method: AP_Arming::Method
// @LoggerMessage: ARSP
// @Description: Airspeed sensor data
// @Field: TimeUS: Time since system startup
// @Field: I: Airspeed sensor instance number
// @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
// @Field: H: True if sensor is healthy
// @Field: Hp: Probability sensor is healthy
// @Field: TR: innovation test ratio
// @Field: Pri: True if sensor is the primary sensor
// @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
// @Field: Force: Force being applied
// @Field: Speed: Current servo movement speed
// @Field: Pow: Amount of rated power being applied
// @Field: PosCmd: commanded servo position
// @Field: V: Voltage
// @Field: A: Current
// @Field: MotT: motor temperature
// @Field: PCBT: PCB temperature
// @Field: Err: error flags
// @LoggerMessage: DMS
// @Description: DataFlash-Over-MAVLink statistics
// @Field: TimeUS: Time since system startup
// @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
// @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
// @LoggerMessage: ERR
// @Description: Specifically coded error messages
// @Field: TimeUS: Time since system startup
// @Field: Subsys: Subsystem in which the error occurred
// @FieldValueEnum: Subsys: LogErrorSubsystem
// @Field: ECode: Subsystem-specific error code
// @LoggerMessage: EV
// @Description: Specifically coded event messages
// @Field: TimeUS: Time since system startup
// @Field: Id: Event identifier
// @FieldValueEnum: Id: LogEvent
// @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
// @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
// @LoggerMessage: FMTU
// @Description: Message defining units and multipliers used for fields of other messages
// @Field: TimeUS: Time since system startup
// @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
// @LoggerMessage: LGR
// @Description: Landing gear information
// @Field: TimeUS: Time since system startup
// @Field: LandingGear: Current landing gear state
// @FieldValueEnum: LandingGear: AP_LandingGear::LG_LandingGear_State
// @Field: WeightOnWheels: Weight on wheels state
// @FieldValueEnum: WeightOnWheels: AP_LandingGear::LG_WOW_State
// @LoggerMessage: MAG
// @Description: Information received from compasses
// @Field: TimeUS: Time since system startup
// @Field: I: magnetometer sensor instance number
// @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
// @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
// @Field: Health: true if the compass is considered healthy
// @Field: S: time measurement was taken
// @LoggerMessage: MAV
// @Description: GCS MAVLink link statistics
// @Field: TimeUS: Time since system startup
// @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
// @FieldBitmaskEnum: flags: GCS_MAVLINK::Flags
// @Field: ss: stream slowdown is the number of ms being added to each message to fit within bandwidth
// @Field: tf: times buffer was full when a message was going to be sent
// @LoggerMessage: MAVC
// @Description: MAVLink command we have just executed
// @Field: TimeUS: Time since system startup
// @Field: TS: target system for command
// @Field: TC: target component for command
// @Field: SS: source system for command
// @Field: SC: source component for command
// @Field: Fr: command frame
// @Field: Cmd: mavlink command enum value
// @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
// @LoggerMessage: MODE
// @Description: vehicle control mode information
// @Field: TimeUS: Time since system startup
// @Field: Mode: vehicle-specific mode number
// @Field: ModeNum: alias for Mode
// @Field: Rsn: reason for entering this mode; enumeration value
// @FieldValueEnum: Rsn: ModeReason
// @LoggerMessage: MSG
// @Description: Textual messages
// @Field: TimeUS: Time since system startup
// @Field: Message: message text
// @LoggerMessage: MULT
// @Description: Message mapping from single character to numeric multiplier
// @Field: TimeUS: Time since system startup
// @Field: Id: character referenced by FMTU
// @Field: Mult: numeric multiplier
// @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 rotational velocity, X-axis
// @Field: bodyY: derived rotational velocity, Y-axis
// @LoggerMessage: PARM
// @Description: parameter value
// @Field: TimeUS: Time since system startup
// @Field: Name: parameter name
// @Field: Value: parameter value
// @Field: Default: default parameter value for this board and config
// @LoggerMessage: PIDR
// @Description: Proportional/Integral/Derivative gain values for Roll rate
// @LoggerMessage: PIDP
// @Description: Proportional/Integral/Derivative gain values for Pitch rate
// @LoggerMessage: PIDY
// @Description: Proportional/Integral/Derivative gain values for Yaw rate
// @LoggerMessage: PIDA
// @Description: Proportional/Integral/Derivative gain values for vertical acceleration
// @LoggerMessage: PIDS
// @Description: Proportional/Integral/Derivative gain values for ground steering yaw rate
// @LoggerMessage: PIDN
// @Description: Proportional/Integral/Derivative gain values for North/South velocity
// @LoggerMessage: PIDE
// @Description: Proportional/Integral/Derivative gain values for East/West velocity
// @Field: TimeUS: Time since system startup
// @Field: Tar: desired value
// @Field: Act: achieved value
// @Field: Err: error between target and achieved
// @Field: P: proportional part of PID
// @Field: I: integral part of PID
// @Field: D: derivative part of PID
// @Field: FF: controller feed-forward portion of response
// @Field: DFF: controller derivative feed-forward portion of response
// @Field: Dmod: scaler applied to D gain to reduce limit cycling
// @Field: SRate: slew rate used in slew limiter
// @Field: Flags: bitmask of PID state flags
// @FieldBitmaskEnum: Flags: log_PID_Flags
// @LoggerMessage: PM
// @Description: autopilot system performance and general data dumping ground
// @Field: TimeUS: Time since system startup
// @Field: LR: Main loop rate
// @Field: NLon: Number of long loops detected
// @Field: NL: 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
// @FieldBitmaskEnum: IntE: AP_InternalError::error_t
// @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
// @Field: SPIC: Number of SPI transactions processed
// @Field: I2CC: Number of i2c transactions processed
// @Field: I2CI: Number of i2c interrupts serviced
// @Field: Ex: number of microseconds being added to each loop to address scheduler overruns
// @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
// @FieldBitmaskEnum: Flags: AP_HAL::AnalogIn::PowerStatusFlag
// @Field: AccFlags: Accumulated System power flags; all flags which have ever been set
// @FieldBitmaskEnum: AccFlags: AP_HAL::AnalogIn::PowerStatusFlag
// @Field: Safety: Hardware Safety Switch status
// @LoggerMessage: MCU
// @Description: MCU voltage and temprature monitering
// @Field: TimeUS: Time since system startup
// @Field: MTemp: Temperature
// @Field: MVolt: Voltage
// @Field: MVmin: Voltage min
// @Field: MVmax: Voltage max
// @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
// @Field: Flags: altitude frame flags
// @LoggerMessage: RCI2
// @Description: (More) RC input channels to vehicle
// @Field: TimeUS: Time since system startup
// @Field: C15: channel 15 input
// @Field: C16: channel 16 input
// @Field: OMask: bitmask of RC channels being overridden by mavlink input
// @Field: Flags: bitmask of RC state flags
// @FieldBitmaskEnum: Flags: AP_Logger::RCLoggingFlags
// @LoggerMessage: RCIN