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_ADSB/GDL90_protocol/GDL90_Message_Structs.h
Views: 1799
1
/*
2
Copyright (C) 2021 Kraus Hamdani Aerospace Inc. All rights reserved.
3
4
This program is free software: you can redistribute it and/or modify
5
it under the terms of the GNU General Public License as published by
6
the Free Software Foundation, either version 3 of the License, or
7
(at your option) any later version.
8
9
This program is distributed in the hope that it will be useful,
10
but WITHOUT ANY WARRANTY; without even the implied warranty of
11
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12
GNU General Public License for more details.
13
14
You should have received a copy of the GNU General Public License
15
along with this program. If not, see <http://www.gnu.org/licenses/>.
16
17
18
Author: GDL90/UCP protocol by uAvionix, 2021.
19
Implemented by: Tom Pittenger
20
*/
21
22
#include <stddef.h>
23
#include <stdbool.h>
24
#include <stdint.h>
25
26
typedef enum __attribute__((__packed__))
27
{
28
GDL90_ID_HEARTBEAT = 0,
29
GDL90_ID_OWNSHIP_REPORT = 10, // 0x0A
30
GDL90_ID_OWNSHIP_GEOMETRIC_ALTITUDE = 11, // 0x0B
31
GDL90_ID_IDENTIFICATION = 37, // 0x25
32
GDL90_ID_SENSOR_MESSAGE = 40, // 0x28
33
GDL90_ID_TRANSPONDER_CONFIG = 43, // 0x2B
34
GDL90_ID_MESSAGE_REQUEST = 44, // 0x2C
35
GDL90_ID_TRANSPONDER_CONTROL = 45, // 0x2D
36
GDL90_ID_GPS_DATA = 46, // 0x2E
37
GDL90_ID_TRANSPONDER_STATUS = 47, // 0x2F
38
} GDL90_MESSAGE_ID;
39
40
typedef enum __attribute__((__packed__))
41
{
42
ADSB_NIC_BARO_UNVERIFIED = 0, // Baro is Gilman bases, and not cross checked
43
ADSB_NIC_BARO_VERIFIED = 1, // Baro is cross-checked, or not Gilman based
44
} ADSB_NIC_BARO; // Barometric Altitude Integrity Code
45
46
typedef enum __attribute__((__packed__))
47
{
48
ADSB_AIRBORNE_SUBSONIC = 0,
49
ADSB_AIRBORNE_SUPERSONIC = 1,
50
ADSB_ON_GROUND = 2,
51
// 3 Reserved
52
} ADSB_AIR_GROUND_STATE; // Determines how horizontal velocity fields are processed in UAT
53
54
typedef enum __attribute__((__packed__))
55
{
56
ADSB_EMERGENCY_NONE = 0,
57
ADSB_EMERGENCY_GENERAL = 1,
58
ADSB_EMERGENCY_MEDICAL = 2,
59
ADSB_EMERGENCY_MINIMUM_FUEL = 3,
60
ADSB_EMERGENCY_NO_COMMUNICATION = 4,
61
ADSB_EMERGNECY_INTERFERENCE = 5,
62
ADSB_EMERGENCY_DOWNED_AIRCRAFT = 6,
63
ADSB_EMERGENCY_UAS_LOST_LINK = 7,
64
// 7 Reserved
65
} ADSB_EMERGENCY_STATUS;
66
67
#define GDL90_TRANSPONDER_CONTROL_VERSION (2)
68
#if GDL90_TRANSPONDER_CONTROL_VERSION == 1
69
typedef struct __attribute__((__packed__))
70
{
71
GDL90_MESSAGE_ID messageId;
72
uint8_t version;
73
ADSB_NIC_BARO baroCrossChecked : 1;
74
ADSB_AIR_GROUND_STATE airGroundState : 2;
75
uint8_t identActive : 1;
76
uint8_t modeAEnabled : 1;
77
uint8_t modeCEnabled : 1;
78
uint8_t modeSEnabled : 1;
79
uint8_t es1090TxEnabled : 1;
80
int32_t externalBaroAltitude_mm;
81
uint16_t squawkCode;
82
ADSB_EMERGENCY_STATUS emergencyState;
83
uint8_t callsign[8];
84
} GDL90_TRANSPONDER_CONTROL_MSG;
85
#elif GDL90_TRANSPONDER_CONTROL_VERSION == 2
86
typedef struct __attribute__((__packed__))
87
{
88
GDL90_MESSAGE_ID messageId;
89
uint8_t version;
90
ADSB_NIC_BARO baroCrossChecked : 1;
91
ADSB_AIR_GROUND_STATE airGroundState : 2;
92
uint8_t identActive : 1;
93
uint8_t modeAEnabled : 1;
94
uint8_t modeCEnabled : 1;
95
uint8_t modeSEnabled : 1;
96
uint8_t es1090TxEnabled : 1;
97
int32_t externalBaroAltitude_mm;
98
uint16_t squawkCode;
99
ADSB_EMERGENCY_STATUS emergencyState;
100
uint8_t callsign[8];
101
uint8_t rfu : 7;
102
uint8_t x_bit : 1;
103
} GDL90_TRANSPONDER_CONTROL_MSG;
104
#endif
105
106
#define GDL90_STATUS_MAX_ALTITUDE_FT (101338)
107
#define GDL90_STATUS_MIN_ALTITUDE_FT (-1000)
108
typedef struct __attribute__((__packed__))
109
{
110
GDL90_MESSAGE_ID messageId;
111
uint8_t version;
112
uint8_t rfu : 2;
113
uint8_t x_bit : 1;
114
uint8_t identActive : 1;
115
uint8_t modeAEnabled : 1;
116
uint8_t modeCEnabled : 1;
117
uint8_t modeSEnabled : 1;
118
uint8_t es1090TxEnabled : 1;
119
uint16_t modeARepliesPerSecond;
120
uint16_t modecRepliesPerSecond;
121
uint16_t modeSRepliesPerSecond;
122
uint16_t squawkCode;
123
uint16_t crc;
124
} GDL90_TRANSPONDER_STATUS_MSG;
125
126
typedef struct __attribute__((__packed__))
127
{
128
GDL90_MESSAGE_ID messageId;
129
uint8_t version;
130
uint8_t indicatingOnGround : 1;
131
uint8_t interrogatedSinceLast : 1;
132
uint8_t fault : 1;
133
uint8_t identActive : 1;
134
uint8_t modeAEnabled : 1;
135
uint8_t modeCEnabled : 1;
136
uint8_t modeSEnabled : 1;
137
uint8_t es1090TxEnabled : 1;
138
uint8_t latitude[3];
139
uint8_t longitude[3];
140
uint32_t track_Heading : 8;
141
uint32_t horizontalVelocity :12;
142
uint32_t altitude :12;
143
uint16_t squawkCode;
144
uint8_t NIC : 4;
145
uint8_t NACp : 4;
146
uint8_t temperature;
147
uint16_t crc;
148
} GDL90_TRANSPONDER_STATUS_MSG_V3;
149
150
151
typedef struct __attribute__((__packed__))
152
{
153
uint8_t HPLfdeActive : 1;
154
uint8_t fault : 1;
155
uint8_t HrdMagNorth : 1;
156
uint8_t reserved : 5;
157
} GDL90_GPS_NAV_STATE;
158
159
typedef enum __attribute__((__packed__))
160
{
161
GPS_FIX_NONE = 0,
162
GPS_FIX_NO_FIX = 1,
163
GPS_FIX_2D = 2,
164
GPS_FIX_3D = 3,
165
GPS_FIX_DIFFERENTIAL = 4,
166
GPS_FIX_RTK = 5,
167
} GPS_FIX;
168
169
typedef struct __attribute__((__packed__))
170
{
171
GDL90_MESSAGE_ID messageId;
172
uint8_t version;
173
uint32_t utcTime_s; // Time since GPS epoch
174
int32_t latitude_ddE7;
175
int32_t longitude_ddE7;
176
int32_t altitudeGnss_mm; // Height about WGS84 ellipsoid
177
// Protection Limits. FD or SBAS-based depending on state bits
178
uint32_t HPL_mm;
179
uint32_t VPL_cm;
180
// FOMS
181
uint32_t horizontalFOM_mm;
182
uint16_t verticalFOM_cm;
183
uint16_t horizontalVelocityFOM_mmps;
184
uint16_t verticalVelocityFOM_mmps;
185
// Velocities
186
int16_t verticalVelocity_cmps;
187
int32_t northVelocity_mmps; // millimeter/s
188
int32_t eastVelocity_mmps;
189
// State
190
GPS_FIX fixType;
191
GDL90_GPS_NAV_STATE navState;
192
uint8_t satsUsed;
193
} GDL90_GPS_DATA_V2;
194
#define GDL90_GPS_DATA_VERSION (2)
195
196
typedef struct __attribute__((__packed__))
197
{
198
GDL90_MESSAGE_ID messageId;
199
uint8_t version;
200
GDL90_MESSAGE_ID reqMsgId;
201
} GDL90_TRANSPONDER_MESSAGE_REQUEST_V2;
202
203
typedef enum __attribute__((__packed__))
204
{
205
GDL90_BARO_DATA_SOURCE_INTERNAL = 0,
206
GDL90_BARO_DATA_SOURCE_EXTERNAL,
207
}GDL90_BARO_DATA_SOURCE;
208
209
typedef enum __attribute__((__packed__))
210
{
211
ADSB_SDA_UNKNOWN = 0,
212
ADSB_SDA_10_NEG3 = 1,
213
ADSB_SDA_10_NEG5 = 2,
214
ADSB_SDA_10_NEG7 = 3,
215
} ADSB_SDA; // System Design Assurance
216
217
typedef enum __attribute__((__packed__))
218
{
219
ADSB_SIL_UNKNOWN = 0,
220
ADSB_SIL_10_NEG3 = 1,
221
ADSB_SIL_10_NEG5 = 2,
222
ADSB_SIL_10_NEG7 = 3,
223
} ADSB_SIL; // Source Integrity Level
224
225
typedef enum __attribute__((__packed__))
226
{
227
ADSB_AV_LW_NO_DATA = 0,
228
ADSB_AV_LW_15M_23M = 1,
229
ADSB_AV_LW_25M_28P5M = 2,
230
ADSB_AV_LW_25M_34M = 3,
231
ADSB_AV_LW_35M_33M = 4,
232
ADSB_AV_LW_35M_38M = 5,
233
ADSB_AV_LW_45M_39P5M = 6,
234
ADSB_AV_LW_45M_45M = 7,
235
ADSB_AV_LW_55M_45M = 8,
236
ADSB_AV_LW_55M_52M = 9,
237
ADSB_AV_LW_65M_59P5M = 10,
238
ADSB_AV_LW_65M_67M = 11,
239
ADSB_AV_LW_75M_72P5M = 12,
240
ADSB_AV_LW_75M_80M = 13,
241
ADSB_AV_LW_85M_80M = 14,
242
ADSB_AV_LW_85M_90M = 15,
243
} ADSB_AIRCRAFT_LENGTH_WIDTH;
244
245
typedef enum __attribute__((__packed__))
246
{
247
ADSB_NOT_UAT_IN_CAPABLE = 0,
248
ADSB_UAT_IN_CAPABLE = 1
249
} ADSB_UAT_IN_CAPABILITY;
250
251
typedef enum __attribute__((__packed__))
252
{
253
ADSB_NOT_1090ES_IN_CAPABLE = 0,
254
ADSB_1090ES_IN_CAPABLE = 1
255
} ADSB_1090ES_IN_CAPABILITY;
256
257
typedef enum __attribute__((__packed__))
258
{
259
ADSB_GPS_LON_NO_DATA = 0,
260
ADSB_GPS_LON_FROM_SENSOR = 1,
261
// 2 - 31 valid values in 2 meter increments
262
} ADSB_GPS_LONGITUDINAL_OFFSET;
263
264
typedef enum __attribute__((__packed__))
265
{
266
ADSB_GPS_LAT_NO_DATA = 0,
267
ADSB_GPS_LAT_LEFT_2M = 1,
268
ADSB_GPS_LAT_LEFT_4M = 2,
269
ADSB_GPS_LAT_LEFT_6M = 3,
270
ADSB_GPS_LAT_0M = 4,
271
ADSB_GPS_LAT_RIGHT_2M = 5,
272
ADSB_GPS_LAT_RIGHT_4M = 6,
273
ADSB_GPS_LAT_RIGHT_6M = 7,
274
} ADSB_GPS_LATERAL_OFFSET;
275
276
typedef enum __attribute__((__packed__))
277
{
278
ADSB_EMITTER_NO_INFO = 0,
279
ADSB_EMITTER_LIGHT = 1,
280
ADSB_EMITTER_SMALL = 2,
281
ADSB_EMITTER_LARGE = 3,
282
ADSB_EMITTER_HIGH_VORTEX_LARGE = 4,
283
ADSB_EMITTER_HEAVY = 5,
284
ADSB_EMITTER_HIGHLY_MANUV = 6,
285
ADSB_EMITTER_ROTOCRAFT = 7,
286
// 8 Unassigned
287
ADSB_EMITTER_GLIDER = 9,
288
ADSB_EMITTER_LIGHTER_AIR = 10,
289
ADSB_EMITTER_PARACHUTE = 11,
290
ADSB_EMITTER_ULTRA_LIGHT = 12,
291
// 13 Unassigned
292
ADSB_EMITTER_UAV = 14,
293
ADSB_EMITTER_SPACE = 15,
294
// 16 Unassigned
295
296
// Surface types
297
ADSB_EMITTER_EMERGENCY_SURFACE = 17,
298
ADSB_EMITTER_SERVICE_SURFACE = 18,
299
300
// Obstacle types
301
ADSB_EMITTER_POINT_OBSTACLE = 19,
302
ADSB_EMITTER_CLUSTER_OBSTACLE = 20,
303
ADSB_EMITTER_LINE_OBSTACLE = 21,
304
// 22 - 39 Reserved
305
} ADSB_EMITTER; // ADSB Emitter Category
306
307
typedef enum __attribute__((__packed__))
308
{
309
PING_COM_1200_BAUD = 0,
310
PING_COM_2400_BAUD = 1,
311
PING_COM_4800_BAUD = 2,
312
PING_COM_9600_BAUD = 3,
313
PING_COM_19200_BAUD = 4,
314
PING_COM_38400_BAUD = 5,
315
PING_COM_57600_BAUD = 6,
316
PING_COM_115200_BAUD = 7,
317
PING_COM_921600_BAUD = 8,
318
} PING_COM_RATE;
319
320
typedef enum __attribute__((__packed__))
321
{
322
CONFIG_VALIDITY_ICAO = 1 << 0,
323
CONFIG_VALIDITY_SIL = 1 << 1,
324
CONFIG_VALIDITY_SDA = 1 << 2,
325
CONFIG_VALIDITY_BARO_ALT_SOURCE = 1 << 3,
326
CONFIG_VALIDITY_AIRCRAFT_MAX_SPEED = 1 << 4,
327
CONFIG_VALIDITY_TEST_MODE = 1 << 5,
328
CONFIG_VALIDITY_ADSB_IN_CAP = 1 << 6,
329
CONFIG_VALIDITY_AIRCRAFT_LEN_WIDTH = 1 << 7,
330
CONFIG_VALIDITY_ANT_LAT_OFFSET = 1 << 8,
331
CONFIG_VALIDITY_ANT_LONG_OFFSET = 1 << 9,
332
CONFIG_VALIDITY_AIRCRAFT_REG = 1 << 10,
333
CONFIG_VALIDITY_AIRCRAFT_STALL_SPEED = 1 << 11,
334
CONFIG_VALIDITY_AIRCRAFT_EMITTER_TYPE = 1 << 12,
335
CONFIG_VALIDITY_DEF_1090ES_TX_MODE = 1 << 13,
336
CONFIG_VALIDITY_DEF_MODES_REPLY_MODE = 1 << 14,
337
CONFIG_VALIDITY_DEF_MODEC_REPLY_MODE = 1 << 15,
338
CONFIG_VALIDITY_DEF_MODEA_REPLY_MODE = 1 << 16,
339
CONFIG_VALIDITY_SERIAL_BAUD_RATE = 1 << 17,
340
CONFIG_VALIDITY_DEF_MODEA_SQUAWK = 1 << 18,
341
CONFIG_VALIDITY_BARO_100 = 1 << 19,
342
CONFIG_VALIDITY_IN_PROTOCOL = 1 << 20,
343
CONFIG_VALIDITY_OUT_PROTOCOL = 1 << 21,
344
} CONFIG_VALIDITY;
345
346
typedef union __attribute__((__packed__))
347
{
348
struct __attribute__((__packed__))
349
{
350
uint32_t icaoValid : 1;
351
uint32_t silValid : 1;
352
uint32_t sdaValid : 1;
353
uint32_t baroAltSourceValid : 1;
354
uint32_t aircraftMaxSpeedValid : 1;
355
uint32_t testModeValid : 1;
356
uint32_t adsbInCapValid : 1;
357
uint32_t aircraftLenWidthValid : 1;
358
uint32_t aircraftLatOffsetValid : 1;
359
uint32_t aircraftLongOffsetValid : 1;
360
uint32_t aircraftRegValid : 1;
361
uint32_t aircraftStallSpeedValid : 1;
362
uint32_t aircraftEmitterCatValid : 1;
363
uint32_t default1090ExTxModeValid : 1;
364
uint32_t defaultModeSReplyModeValid : 1;
365
uint32_t defaultModeCReplyModeValid : 1;
366
uint32_t defaultModeAReplyModeValid : 1;
367
uint32_t serialBaudRateValid : 1;
368
uint32_t defaultModeASquawkValid : 1;
369
uint32_t baro100Valid : 1;
370
uint32_t inProtocolValid : 1;
371
uint32_t outProtocolValid : 1;
372
uint32_t reserved : 10;
373
};
374
CONFIG_VALIDITY raw;
375
} CONFIG_VALIDITY_BITMASK;
376
377
typedef enum __attribute__((__packed__))
378
{
379
PING_PROTOCOL_NONE = 0,
380
PING_PROTOCOL_MAVLINK = 1 << 0,
381
PING_PROTOCOL_UCP = 1 << 1,
382
PING_PROTOCOL_APOLLO = 1 << 9,
383
PING_PROTOCOL_UCP_HD = 1 << 10,
384
} PING_PROTOCOL;
385
386
typedef union
387
{
388
struct __attribute__((__packed__))
389
{
390
uint16_t mavlink : 1;
391
uint16_t ucp : 1;
392
uint16_t reserved1 : 7;
393
uint16_t apollo : 1;
394
uint16_t ucphd : 1;
395
uint16_t reserved2 : 5;
396
};
397
PING_PROTOCOL raw;
398
} PING_PROTOCOL_MASK;
399
400
typedef struct __attribute__((__packed__))
401
{
402
GDL90_MESSAGE_ID messageId;
403
uint8_t version;
404
uint8_t icaoAddress[3];
405
uint8_t maxSpeed : 3;
406
GDL90_BARO_DATA_SOURCE baroAltSource : 1;
407
ADSB_SDA SDA : 2;
408
ADSB_SIL SIL : 2;
409
ADSB_AIRCRAFT_LENGTH_WIDTH lengthWidth : 4;
410
ADSB_1090ES_IN_CAPABILITY es1090InCapable : 1;
411
ADSB_UAT_IN_CAPABILITY uatInCapable : 1;
412
uint8_t testMode : 2;
413
ADSB_GPS_LONGITUDINAL_OFFSET longitudinalOffset : 5;
414
ADSB_GPS_LATERAL_OFFSET lateralOffset : 3;
415
uint8_t registration[8];
416
uint16_t stallSpeed_cmps;
417
ADSB_EMITTER emitterType;
418
PING_COM_RATE baudRate : 4;
419
uint8_t modeAEnabled : 1;
420
uint8_t modeCEnabled : 1;
421
uint8_t modeSEnabled : 1;
422
uint8_t es1090TxEnabled : 1;
423
uint16_t defaultSquawk;
424
CONFIG_VALIDITY_BITMASK valdityBitmask;
425
uint8_t rfu : 7;
426
uint8_t baro100 : 1;
427
PING_PROTOCOL_MASK inProtocol;
428
PING_PROTOCOL_MASK outProtocol;
429
uint16_t crc;
430
} GDL90_TRANSPONDER_CONFIG_MSG_V4_V5;
431
432
433
typedef struct __attribute__((__packed__))
434
{
435
uint8_t fwMajorVersion;
436
uint8_t fwMinorVersion;
437
uint8_t fwBuildVersion;
438
uint8_t hwId; // TODO Ugh should be 16 bits
439
uint64_t serialNumber;
440
} GDL90_DEVICE_ID;
441
442
typedef struct __attribute__((__packed__))
443
{
444
GDL90_MESSAGE_ID messageId;
445
uint8_t protocolVersion;
446
GDL90_DEVICE_ID primary;
447
GDL90_DEVICE_ID secondary;
448
uint8_t primaryFWID;
449
uint32_t primaryCRC;
450
uint8_t secondaryFWID;
451
uint32_t secondaryCRC;
452
uint8_t primaryFwPartNumber[15];
453
uint8_t secondaryFwPartNumber[15];
454
uint16_t crc;
455
} GDL90_IDENTIFICATION_V3;
456
#define GDL90_IDENT_PROTOCOL_VERSION (3)
457
458
459
typedef struct __attribute__((__packed__))
460
{
461
struct
462
{
463
uint8_t uatInitialized : 1;
464
465
// GDL90 public spec defines next bit as reserved
466
// uAvionix maps extra failure condition
467
uint8_t functionFailureGnssDataFrequency : 1;
468
469
uint8_t ratcs : 1;
470
uint8_t gpsBatteryLow : 1;
471
uint8_t addressType : 1;
472
uint8_t ident : 1;
473
uint8_t maintenanceRequired : 1;
474
uint8_t gpsPositionValid : 1;
475
} one;
476
struct __attribute__((__packed__))
477
{
478
479
uint8_t utcOk : 1;
480
481
// GDL90 public spec defines next four bits as reserved
482
// uAvionix maps extra failure conditions
483
uint8_t functionFailureGnssUnavailable : 1;
484
uint8_t functionFailureGnssNo3dFix : 1;
485
uint8_t functionFailureBroadcastMonitor : 1;
486
uint8_t functionFailureTransmitSystem : 1;
487
488
uint8_t csaNotAvailable : 1;
489
uint8_t csaRequested : 1;
490
uint8_t timestampMsb : 1;
491
} two;
492
} GDL90_HEARTBEAT_STATUS;
493
494
typedef struct __attribute__((__packed__))
495
{
496
GDL90_MESSAGE_ID messageId;
497
GDL90_HEARTBEAT_STATUS status;
498
uint16_t timestamp;
499
500
// Need to flip before TX
501
union
502
{
503
struct __attribute__((__packed__))
504
{
505
uint16_t uatMessages : 10;
506
uint16_t rfu : 1;
507
uint16_t uplinkMessages : 5;
508
};
509
uint16_t messageCount;
510
};
511
uint16_t crc;
512
} GDL90_HEARTBEAT;
513
514
typedef enum __attribute__((__packed__))
515
{
516
GDL90_ADDRESS_ADSB_ICAO,
517
GDL90_ADDRESS_ADSB_SELF_ASSIGNED,
518
GDL90_ADDRESS_TISB_ICAO,
519
GDL90_ADDRESS_TISB_TRACK_ID,
520
GDL90_ADDRESS_SURFACE,
521
GDL90_ADDRESS_GROUND_BEACON,
522
} GDL90_ADDRESS_TYPE;
523
524
typedef enum __attribute__((__packed__))
525
{
526
GDL90_NO_ALERT,
527
GDL90_ALERT,
528
} GDL90_TRAFFIC_ALERT;
529
530
typedef enum __attribute__((__packed__))
531
{
532
GDL90_MISC_INVALID,
533
GDL90_MISC_TRUE_TRACK,
534
GDL90_MISC_HEADING_MAGNETIC,
535
GDL90_MISC_HEADING_TRUE,
536
} GDL90_MISC_TRACK_TYPE;
537
538
typedef enum __attribute__((__packed__))
539
{
540
GDL90_MISC_REPORT_UPDATED,
541
GDL90_MISC_REPORT_EXTRAPOLATED,
542
} GDL90_MISC_REPORT_TYPE;
543
544
typedef enum __attribute__((__packed__))
545
{
546
GDL90_MISC_ON_GROUND,
547
GDL90_MISC_AIRBORNE,
548
} GDL90_MISC_AG_STATE;
549
550
typedef union
551
{
552
struct __attribute__((__packed__))
553
{
554
GDL90_MISC_TRACK_TYPE track : 2;
555
GDL90_MISC_REPORT_TYPE reportType : 1;
556
GDL90_MISC_AG_STATE agState : 1;
557
};
558
uint8_t data;
559
} GDL90_MISCELLANEOUS;
560
561
typedef struct __attribute__((__packed__))
562
{
563
GDL90_ADDRESS_TYPE addressType: 4;
564
GDL90_TRAFFIC_ALERT trafficAlert : 4;
565
566
uint8_t address[3];
567
568
uint8_t latitude[3]; // 180 deg / 2^23
569
uint8_t longitude[3]; // 180 deg / 2^23
570
571
// Byte order must be flipped before TX
572
union
573
{
574
struct __attribute__((__packed__))
575
{
576
uint16_t misc : 4;
577
uint16_t altitude : 12;
578
};
579
uint16_t altitudeMisc;
580
};
581
582
uint8_t NACp : 4;
583
uint8_t NIC : 4;
584
585
// Byte order must be flipped before TX
586
union
587
{
588
struct __attribute__((__packed__))
589
{
590
uint32_t heading : 8;
591
uint32_t verticalVelocity : 12;
592
uint32_t horizontalVelocity : 12;
593
};
594
uint32_t velocities;
595
};
596
597
uint8_t emitterCategory;
598
uint8_t callsign[8];
599
600
uint8_t rfu : 4;
601
uint8_t emergencyCode : 4;
602
} GDL90_REPORT;
603
604
typedef struct __attribute__((__packed__))
605
{
606
GDL90_MESSAGE_ID messageId;
607
GDL90_REPORT report;
608
uint16_t crc;
609
} GDL90_OWNSHIP_REPORT;
610
typedef GDL90_OWNSHIP_REPORT GDL90_TRAFFIC_REPORT;
611
612
typedef enum __attribute__((__packed__))
613
{
614
GDL90_NO_WARNING,
615
GDL90_WARNING,
616
} GDL90_VERTICAL_WARNING;
617
618
typedef struct __attribute__((__packed__))
619
{
620
GDL90_MESSAGE_ID messageId;
621
uint16_t geometricAltitude; // 5 ft resolution
622
623
// Must be endian swapped before TX
624
union
625
{
626
struct __attribute__((__packed__))
627
{
628
uint16_t verticalFOM : 15;
629
GDL90_VERTICAL_WARNING verticalWarning : 1;
630
};
631
uint16_t veritcalMetrics;
632
};
633
uint16_t crc;
634
} GDL90_OWNSHIP_GEO_ALTITUDE;
635
636
typedef enum __attribute__((__packed__))
637
{
638
GDL90_SENSOR_AHRS = 0,
639
GDL90_SENSOR_BARO = 1,
640
GDL90_SENSOR_CO = 2,
641
GDL90_SENSOR_DEVICE = 3
642
} GDL90_SENSOR_TYPE;
643
644
typedef struct __attribute__((__packed__))
645
{
646
GDL90_MESSAGE_ID messageId;
647
GDL90_SENSOR_TYPE sensorType;
648
uint32_t pressure_mbarE2;
649
int32_t pressureAlt_mm;
650
int16_t temperature_cE2;
651
uint16_t crc;
652
} GDL90_SENSOR_BARO_MESSAGE;
653
654
655