CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_DAL/LogStructure.h
Views: 1798
1
#pragma once
2
3
#include <AP_Logger/LogStructure.h>
4
#include <AP_Math/vector3.h>
5
#include <AP_Math/vector2.h>
6
#include <AP_Math/matrix3.h>
7
#include <AP_Math/quaternion.h>
8
9
#define LOG_IDS_FROM_DAL \
10
LOG_RFRH_MSG, \
11
LOG_RFRF_MSG, \
12
LOG_REV2_MSG, \
13
LOG_RSO2_MSG, \
14
LOG_RWA2_MSG, \
15
LOG_REV3_MSG, \
16
LOG_RSO3_MSG, \
17
LOG_RWA3_MSG, \
18
LOG_REY3_MSG, \
19
LOG_RFRN_MSG, \
20
LOG_RISH_MSG, \
21
LOG_RISI_MSG, \
22
LOG_RBRH_MSG, \
23
LOG_RBRI_MSG, \
24
LOG_RRNH_MSG, \
25
LOG_RRNI_MSG, \
26
LOG_RGPH_MSG, \
27
LOG_RGPI_MSG, \
28
LOG_RGPJ_MSG, \
29
LOG_RASH_MSG, \
30
LOG_RASI_MSG, \
31
LOG_RBCH_MSG, \
32
LOG_RBCI_MSG, \
33
LOG_RVOH_MSG, \
34
LOG_RMGH_MSG, \
35
LOG_RMGI_MSG, \
36
LOG_ROFH_MSG, \
37
LOG_REPH_MSG, \
38
LOG_RSLL_MSG, \
39
LOG_REVH_MSG, \
40
LOG_RWOH_MSG, \
41
LOG_RBOH_MSG
42
43
// @LoggerMessage: RFRH
44
// @Description: Replay FRame Header
45
struct log_RFRH {
46
uint64_t time_us;
47
uint32_t time_flying_ms;
48
uint8_t _end;
49
};
50
51
// @LoggerMessage: RFRF
52
// @Description: Replay FRame data - Finished frame
53
struct log_RFRF {
54
uint8_t frame_types;
55
uint8_t core_slow;
56
uint8_t _end;
57
};
58
59
// @LoggerMessage: RFRN
60
// @Description: Replay FRame - aNother frame header
61
struct log_RFRN {
62
int32_t lat;
63
int32_t lng;
64
int32_t alt;
65
float EAS2TAS;
66
uint32_t available_memory;
67
Vector3f ahrs_trim;
68
uint8_t vehicle_class;
69
uint8_t ekf_type;
70
uint8_t armed:1;
71
uint8_t unused:1; // was get_compass_is_null
72
uint8_t fly_forward:1;
73
uint8_t ahrs_airspeed_sensor_enabled:1;
74
uint8_t opticalflow_enabled:1;
75
uint8_t wheelencoder_enabled:1;
76
uint8_t takeoff_expected:1;
77
uint8_t touchdown_expected:1;
78
uint8_t _end;
79
};
80
81
// @LoggerMessage: RISH
82
// @Description: Replay Inertial Sensor header
83
struct log_RISH {
84
uint16_t loop_rate_hz;
85
uint8_t first_usable_gyro;
86
uint8_t first_usable_accel;
87
float loop_delta_t;
88
uint8_t accel_count;
89
uint8_t gyro_count;
90
uint8_t _end;
91
};
92
93
// @LoggerMessage: RISI
94
// @Description: Replay Inertial Sensor instance data
95
struct log_RISI {
96
Vector3f delta_velocity;
97
Vector3f delta_angle;
98
float delta_velocity_dt;
99
float delta_angle_dt;
100
uint8_t use_accel:1;
101
uint8_t use_gyro:1;
102
uint8_t get_delta_velocity_ret:1;
103
uint8_t get_delta_angle_ret:1;
104
uint8_t instance;
105
uint8_t _end;
106
};
107
108
// @LoggerMessage: REV2
109
// @Description: Replay Event (EKF2)
110
struct log_REV2 {
111
uint8_t event;
112
uint8_t _end;
113
};
114
115
// @LoggerMessage: RSO2
116
// @Description: Replay Set Origin event (EKF2)
117
struct log_RSO2 {
118
int32_t lat;
119
int32_t lng;
120
int32_t alt;
121
uint8_t _end;
122
};
123
124
// @LoggerMessage: RWA2
125
// @Description: Replay set-default-airspeed event (EKF2)
126
struct log_RWA2 {
127
float airspeed;
128
float uncertainty;
129
uint8_t _end;
130
};
131
132
// same structures for EKF3
133
// @LoggerMessage: REV3
134
// @Description: Replay Event (EKF3)
135
#define log_REV3 log_REV2
136
// @LoggerMessage: RSO3
137
// @Description: Replay Set Origin event (EKF3)
138
#define log_RSO3 log_RSO2
139
// @LoggerMessage: RWA3
140
// @Description: Replay set-default-airspeed event (EKF3)
141
#define log_RWA3 log_RWA2
142
143
// @LoggerMessage: REY3
144
// @Description: Replay Euler Yaw event
145
struct log_REY3 {
146
float yawangle;
147
float yawangleerr;
148
uint32_t timestamp_ms;
149
uint8_t type;
150
uint8_t _end;
151
};
152
153
// @LoggerMessage: RBRH
154
// @Description: Replay Data Barometer Header
155
struct log_RBRH {
156
uint8_t primary;
157
uint8_t num_instances;
158
uint8_t _end;
159
};
160
161
// @LoggerMessage: RBRI
162
// @Description: Replay Data Barometer Instance
163
struct log_RBRI {
164
uint32_t last_update_ms;
165
float altitude; // from get_altitude
166
bool healthy;
167
uint8_t instance;
168
uint8_t _end;
169
};
170
171
// @LoggerMessage: RRNH
172
// @Description: Replay Data Rangefinder Header
173
struct log_RRNH {
174
// this is rotation-pitch-270!
175
int16_t ground_clearance_cm;
176
int16_t max_distance_cm;
177
uint8_t num_sensors;
178
uint8_t _end;
179
};
180
181
// @LoggerMessage: RRNI
182
// @Description: Replay Data Rangefinder Instance
183
struct log_RRNI {
184
Vector3f pos_offset;
185
uint16_t distance_cm;
186
uint8_t orientation;
187
uint8_t status;
188
uint8_t instance;
189
uint8_t _end;
190
};
191
192
// @LoggerMessage: RGPH
193
// @Description: Replay Data GPS Header
194
struct log_RGPH {
195
uint8_t num_sensors;
196
uint8_t primary_sensor;
197
uint8_t _end;
198
};
199
200
// @LoggerMessage: RGPI
201
// @Description: Replay Data GPS Instance, infrequently changing data
202
struct log_RGPI {
203
Vector3f antenna_offset;
204
float lag_sec;
205
uint8_t have_vertical_velocity:1;
206
uint8_t horizontal_accuracy_returncode:1;
207
uint8_t vertical_accuracy_returncode:1;
208
uint8_t get_lag_returncode:1;
209
uint8_t speed_accuracy_returncode:1;
210
uint8_t gps_yaw_deg_returncode:1;
211
uint8_t status;
212
uint8_t num_sats;
213
uint8_t instance;
214
uint8_t _end;
215
};
216
217
// @LoggerMessage: RGPJ
218
// @Description: Replay Data GPS Instance - rapidly changing data
219
struct log_RGPJ {
220
uint32_t last_message_time_ms;
221
Vector3f velocity;
222
float sacc;
223
float yaw_deg;
224
float yaw_accuracy_deg;
225
uint32_t yaw_deg_time_ms;
226
int32_t lat;
227
int32_t lng;
228
int32_t alt;
229
float hacc;
230
float vacc;
231
uint16_t hdop;
232
uint8_t instance;
233
uint8_t _end;
234
};
235
236
// @LoggerMessage: RASH
237
// @Description: Replay Airspeed Sensor Header
238
struct log_RASH {
239
uint8_t num_sensors;
240
uint8_t primary;
241
uint8_t _end;
242
};
243
244
// @LoggerMessage: RASI
245
// @Description: Replay Airspeed Sensor Instance data
246
struct log_RASI {
247
float airspeed;
248
uint32_t last_update_ms;
249
bool healthy;
250
bool use;
251
uint8_t instance;
252
uint8_t _end;
253
};
254
255
// @LoggerMessage: RMGH
256
// @Description: Replay Data Magnetometer Header
257
struct log_RMGH {
258
float declination;
259
bool available;
260
uint8_t count;
261
bool auto_declination_enabled;
262
uint8_t num_enabled;
263
bool learn_offsets_enabled;
264
bool consistent;
265
uint8_t first_usable;
266
uint8_t _end;
267
};
268
269
// @LoggerMessage: RMGI
270
// @Description: Replay Data Magnetometer Instance
271
struct log_RMGI {
272
uint32_t last_update_usec;
273
Vector3f offsets;
274
Vector3f field;
275
bool use_for_yaw;
276
bool healthy;
277
bool have_scale_factor;
278
uint8_t instance;
279
uint8_t _end;
280
};
281
282
// @LoggerMessage: RBCH
283
// @Description: Replay Data Beacon Header
284
struct log_RBCH {
285
Vector3f vehicle_position_ned;
286
float accuracy_estimate;
287
int32_t origin_lat;
288
int32_t origin_lng;
289
int32_t origin_alt;
290
uint8_t get_vehicle_position_ned_returncode:1;
291
uint8_t get_origin_returncode:1;
292
uint8_t enabled:1;
293
uint8_t count;
294
uint8_t _end;
295
};
296
297
// @LoggerMessage: RBCI
298
// @Description: Replay Data Beacon Instance
299
struct log_RBCI {
300
uint32_t last_update_ms;
301
Vector3f position;
302
float distance;
303
uint8_t healthy;
304
uint8_t instance;
305
uint8_t _end;
306
};
307
308
// @LoggerMessage: RVOH
309
// @Description: Replay Data Visual Odometry data
310
struct log_RVOH {
311
Vector3f pos_offset;
312
uint32_t delay_ms;
313
uint8_t healthy;
314
bool enabled;
315
uint8_t _end;
316
};
317
318
// @LoggerMessage: ROFH
319
// @Description: Replay optical flow data
320
struct log_ROFH {
321
Vector2f rawFlowRates;
322
Vector2f rawGyroRates;
323
uint32_t msecFlowMeas;
324
Vector3f posOffset;
325
float heightOverride;
326
uint8_t rawFlowQuality;
327
uint8_t _end;
328
};
329
330
// @LoggerMessage: REPH
331
// @Description: Replay external position data
332
struct log_REPH {
333
Vector3f pos;
334
Quaternion quat;
335
float posErr;
336
float angErr;
337
uint32_t timeStamp_ms;
338
uint32_t resetTime_ms;
339
uint16_t delay_ms;
340
uint8_t _end;
341
};
342
343
// @LoggerMessage: RSLL
344
// @Description: Replay Set Lat Lng event
345
struct log_RSLL {
346
int32_t lat; // WGS-84 latitude in 1E-7 degrees
347
int32_t lng; // WGS-84 longitude in 1E7 degrees
348
float posAccSD; // horizontal position 1 STD uncertainty (m)
349
uint32_t timestamp_ms;
350
uint8_t _end;
351
};
352
353
// @LoggerMessage: REVH
354
// @Description: Replay external position data
355
struct log_REVH {
356
Vector3f vel;
357
float err;
358
uint32_t timeStamp_ms;
359
uint16_t delay_ms;
360
uint8_t _end;
361
};
362
363
// @LoggerMessage: RWOH
364
// @Description: Replay wheel odometry data
365
struct log_RWOH {
366
float delAng;
367
float delTime;
368
uint32_t timeStamp_ms;
369
Vector3f posOffset;
370
float radius;
371
uint8_t _end;
372
};
373
374
// @LoggerMessage: RBOH
375
// @Description: Replay body odometry data
376
struct log_RBOH {
377
float quality;
378
Vector3f delPos;
379
Vector3f delAng;
380
float delTime;
381
uint32_t timeStamp_ms;
382
Vector3f posOffset;
383
uint16_t delay_ms;
384
uint8_t _end;
385
};
386
387
#define RLOG_SIZE(sname) 3+offsetof(struct log_ ##sname,_end)
388
389
#define LOG_STRUCTURE_FROM_DAL \
390
{ LOG_RFRH_MSG, RLOG_SIZE(RFRH), \
391
"RFRH", "QI", "TimeUS,TF", "s-", "F-" }, \
392
{ LOG_RFRF_MSG, RLOG_SIZE(RFRF), \
393
"RFRF", "BB", "FTypes,Slow", "--", "--" }, \
394
{ LOG_RFRN_MSG, RLOG_SIZE(RFRN), \
395
"RFRN", "IIIfIfffBBB", "HLat,HLon,HAlt,E2T,AM,TX,TY,TZ,VC,EKT,Flags", "DUm????????", "GGB--------" }, \
396
{ LOG_REV2_MSG, RLOG_SIZE(REV2), \
397
"REV2", "B", "Event", "-", "-" }, \
398
{ LOG_RSO2_MSG, RLOG_SIZE(RSO2), \
399
"RSO2", "III", "Lat,Lon,Alt", "DUm", "GGB" }, \
400
{ LOG_RWA2_MSG, RLOG_SIZE(RWA2), \
401
"RWA2", "ff", "Airspeed,uncertainty", "nn", "00" }, \
402
{ LOG_REV3_MSG, RLOG_SIZE(REV3), \
403
"REV3", "B", "Event", "-", "-" }, \
404
{ LOG_RSO3_MSG, RLOG_SIZE(RSO3), \
405
"RSO3", "III", "Lat,Lon,Alt", "DUm", "GGB" }, \
406
{ LOG_RWA3_MSG, RLOG_SIZE(RWA3), \
407
"RWA3", "ff", "Airspeed,Uncertainty", "nn", "00" }, \
408
{ LOG_REY3_MSG, RLOG_SIZE(REY3), \
409
"REY3", "ffIB", "yawangle,yawangleerr,timestamp_ms,type", "???-", "???-" }, \
410
{ LOG_RISH_MSG, RLOG_SIZE(RISH), \
411
"RISH", "HBBfBB", "LR,PG,PA,LD,AC,GC", "------", "------" }, \
412
{ LOG_RISI_MSG, RLOG_SIZE(RISI), \
413
"RISI", "ffffffffBB", "DVX,DVY,DVZ,DAX,DAY,DAZ,DVDT,DADT,Flags,I", "---------#", "----------" }, \
414
{ LOG_RASH_MSG, RLOG_SIZE(RASH), \
415
"RASH", "BB", "Primary,NumInst", "--", "--" }, \
416
{ LOG_RASI_MSG, RLOG_SIZE(RASI), \
417
"RASI", "fIBBB", "pd,UpdateMS,H,Use,I", "----#", "-----" }, \
418
{ LOG_RBRH_MSG, RLOG_SIZE(RBRH), \
419
"RBRH", "BB", "Primary,NumInst", "--", "--" }, \
420
{ LOG_RBRI_MSG, RLOG_SIZE(RBRI), \
421
"RBRI", "IfBB", "LastUpdate,Alt,H,I", "---#", "----" }, \
422
{ LOG_RRNH_MSG, RLOG_SIZE(RRNH), \
423
"RRNH", "hhB", "GCl,MaxD,NumSensors", "???", "???" }, \
424
{ LOG_RRNI_MSG, RLOG_SIZE(RRNI), \
425
"RRNI", "fffHBBB", "PX,PY,PZ,Dist,Orient,Status,I", "------#", "-------" }, \
426
{ LOG_RGPH_MSG, RLOG_SIZE(RGPH), \
427
"RGPH", "BB", "NumInst,Primary", "--", "--" }, \
428
{ LOG_RGPI_MSG, RLOG_SIZE(RGPI), \
429
"RGPI", "ffffBBBB", "OX,OY,OZ,Lg,Flags,Stat,NSats,I", "-------#", "--------" }, \
430
{ LOG_RGPJ_MSG, RLOG_SIZE(RGPJ), \
431
"RGPJ", "IffffffIiiiffHB", "TS,VX,VY,VZ,SA,Y,YA,YT,Lat,Lon,Alt,HA,VA,HD,I", "--------------#", "---------------" }, \
432
{ LOG_RMGH_MSG, RLOG_SIZE(RMGH), \
433
"RMGH", "fBBBBBBB", "Dec,Avail,NumInst,AutoDec,NumEna,LOE,C,FUsable", "--------", "--------" }, \
434
{ LOG_RMGI_MSG, RLOG_SIZE(RMGI), \
435
"RMGI", "IffffffBBBB", "LU,OX,OY,OZ,FX,FY,FZ,UFY,H,HSF,I", "----------#", "-----------" }, \
436
{ LOG_RBCH_MSG, RLOG_SIZE(RBCH), \
437
"RBCH", "ffffiiiBB", "PX,PY,PZ,AE,OLat,OLng,OAlt,Flags,NumInst", "---------", "---------" }, \
438
{ LOG_RBCI_MSG, RLOG_SIZE(RBCI), \
439
"RBCI", "IffffBB", "LU,PX,PY,PZ,Dist,H,I", "smmmm-#", "?0000--" }, \
440
{ LOG_RVOH_MSG, RLOG_SIZE(RVOH), \
441
"RVOH", "fffIBB", "OX,OY,OZ,Del,H,Ena", "------", "------" }, \
442
{ LOG_ROFH_MSG, RLOG_SIZE(ROFH), \
443
"ROFH", "ffffIffffB", "FX,FY,GX,GY,Tms,PX,PY,PZ,HgtOvr,Qual", "----------", "----------" }, \
444
{ LOG_REPH_MSG, RLOG_SIZE(REPH), \
445
"REPH", "fffffffffIIH", "PX,PY,PZ,Q1,Q2,Q3,Q4,PEr,AEr,TS,RT,D", "------------", "------------" }, \
446
{ LOG_RSLL_MSG, RLOG_SIZE(RSLL), \
447
"RSLL", "IIfI", "Lat,Lng,PosAccSD,TS", "DU--", "GG--" }, \
448
{ LOG_REVH_MSG, RLOG_SIZE(REVH), \
449
"REVH", "ffffIH", "VX,VY,VZ,Er,TS,D", "------", "------" }, \
450
{ LOG_RWOH_MSG, RLOG_SIZE(RWOH), \
451
"RWOH", "ffIffff", "DA,DT,TS,PX,PY,PZ,R", "-------", "-------" }, \
452
{ LOG_RBOH_MSG, RLOG_SIZE(RBOH), \
453
"RBOH", "ffffffffIfffH", "Q,DPX,DPY,DPZ,DAX,DAY,DAZ,DT,TS,OX,OY,OZ,D", "-------------", "-------------" },
454
455