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/sagetech-sdk/sg.h
Views: 1799
1
/**
2
* @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved.
3
*
4
* @file sg.h
5
* @author jimb
6
*
7
* @date Feb 10, 2021
8
*
9
* Sagetech protocol for host message building and parsing.
10
*
11
* This module performs both the following:
12
* 1. Parses raw Sagetech host messages defined in the SDIM and
13
* returns a populated struct dataset of the message type.
14
* 2. Receives a populated struct dataset of the desired host message
15
* and returns the corresponding raw message data buffer.
16
*/
17
18
#ifndef SG_H
19
#define SG_H
20
21
#include <stdint.h>
22
#include <stdbool.h>
23
24
/// Host Message Lengths (bytes)
25
#define SG_MSG_LEN_INSTALL 41
26
#define SG_MSG_LEN_FLIGHT 17
27
#define SG_MSG_LEN_OPMSG 17
28
#define SG_MSG_LEN_GPS 68
29
#define SG_MSG_LEN_DATAREQ 9
30
#define SG_MSG_LEN_TARGETREQ 12
31
#define SG_MSG_LEN_MODE 10
32
33
/// Host Message Types
34
#define SG_MSG_TYPE_HOST_INSTALL 0x01
35
#define SG_MSG_TYPE_HOST_FLIGHT 0x02
36
#define SG_MSG_TYPE_HOST_OPMSG 0x03
37
#define SG_MSG_TYPE_HOST_GPS 0x04
38
#define SG_MSG_TYPE_HOST_DATAREQ 0x05
39
#define SG_MSG_TYPE_HOST_TARGETREQ 0x0B
40
#define SG_MSG_TYPE_HOST_MODE 0x0C
41
42
/// XPNDR Message Types
43
#define SG_MSG_TYPE_XPNDR_ACK 0x80
44
#define SG_MSG_TYPE_XPNDR_INSTALL 0x81
45
#define SG_MSG_TYPE_XPNDR_FLIGHT 0x82
46
#define SG_MSG_TYPE_XPNDR_STATUS 0x83
47
#define SG_MSG_TYPE_XPNDR_COMMA 0x85
48
#define SG_MSG_TYPE_XPNDR_MODE 0x8C
49
#define SG_MSG_TYPE_XPNDR_VERSION 0x8E
50
#define SG_MSG_TYPE_XPNDR_SERIALNUM 0x8F
51
52
/// ADS-B Message Types
53
#define SG_MSG_TYPE_ADSB_TSUMMARY 0x90
54
#define SG_MSG_TYPE_ADSB_SVR 0x91
55
#define SG_MSG_TYPE_ADSB_MSR 0x92
56
#define SG_MSG_TYPE_ADSB_TSTATE 0x97
57
#define SG_MSG_TYPE_ADSB_ARVR 0x98
58
59
/// Start byte for all host messages
60
#define SG_MSG_START_BYTE 0xAA
61
62
/// Emitter category set byte values
63
#define SG_EMIT_GROUP_A 0x00
64
#define SG_EMIT_GROUP_B 0x01
65
#define SG_EMIT_GROUP_C 0x02
66
#define SG_EMIT_GROUP_D 0x03
67
68
/// Emitter category enumeration offsets
69
#define SG_EMIT_OFFSET_A 0x00
70
#define SG_EMIT_OFFSET_B 0x10
71
#define SG_EMIT_OFFSET_C 0x20
72
#define SG_EMIT_OFFSET_D 0x30
73
74
/**
75
* Available COM port baud rates.
76
*/
77
typedef enum
78
{
79
baud38400 = 0,
80
baud600,
81
baud4800,
82
baud9600,
83
baud28800,
84
baud57600,
85
baud115200,
86
baud230400,
87
baud19200,
88
baud460800,
89
baud921600
90
} sg_baud_t;
91
92
/**
93
* Transponder ethernet configuration
94
*/
95
typedef struct
96
{
97
uint32_t ipAddress; /// The transponder ip address
98
uint32_t subnetMask; /// The transponder subnet mask
99
uint16_t portNumber; /// The transponder port number
100
} sg_ethernet_t;
101
102
/**
103
* Available GPS integrity SIL values
104
*/
105
typedef enum
106
{
107
silUnknown = 0,
108
silLow,
109
silMedium,
110
silHigh
111
} sg_sil_t;
112
113
/**
114
* Available GPS integrity SDA values
115
*/
116
typedef enum
117
{
118
sdaUnknown = 0,
119
sdaMinor,
120
sdaMajor,
121
sdaHazardous
122
} sg_sda_t;
123
124
/**
125
* Available emitter types
126
*/
127
typedef enum
128
{
129
aUnknown = SG_EMIT_OFFSET_A,
130
aLight,
131
aSmall,
132
aLarge,
133
aHighVortex,
134
aHeavy,
135
aPerformance,
136
aRotorCraft,
137
bUnknown = SG_EMIT_OFFSET_B,
138
bGlider,
139
bAir,
140
bParachutist,
141
bUltralight,
142
bUAV = SG_EMIT_OFFSET_B + 6,
143
bSpace,
144
cUnknown = SG_EMIT_OFFSET_C,
145
cEmergency,
146
cService,
147
cPoint,
148
cCluster,
149
cLine,
150
dUnknown = SG_EMIT_OFFSET_D
151
} sg_emitter_t;
152
153
/**
154
* Available aircraft sizes in meters
155
*/
156
typedef enum
157
{
158
sizeUnknown = 0, /// Dimensions unknown
159
sizeL15W23, /// Length <= 15m & Width <= 23m
160
sizeL25W28, /// Length <= 25m & Width <= 28.5m
161
sizeL25W34, /// Length <= 25m & Width <= 34m
162
sizeL35W33, /// Length <= 35m & Width <= 33m
163
sizeL35W38, /// Length <= 35m & Width <= 38m
164
sizeL45W39, /// Length <= 45m & Width <= 39.5m
165
sizeL45W45, /// Length <= 45m & Width <= 45m
166
sizeL55W45, /// Length <= 55m & Width <= 45m
167
sizeL55W52, /// Length <= 55m & Width <= 52m
168
sizeL65W59, /// Length <= 65m & Width <= 59.5m
169
sizeL65W67, /// Length <= 65m & Width <= 67m
170
sizeL75W72, /// Length <= 75m & Width <= 72.5m
171
sizeL75W80, /// Length <= 75m & Width <= 80m
172
sizeL85W80, /// Length <= 85m & Width <= 80m
173
sizeL85W90 /// Length <= 85m & Width <= 90m
174
} sg_size_t;
175
176
/**
177
* Available aircraft maximum airspeeds
178
*/
179
typedef enum
180
{
181
speedUnknown = 0, /// Max speed unknown
182
speed75kt, /// 0 knots < Max speed < 75 knots
183
speed150kt, /// 75 knots < Max speed < 150 knots
184
speed300kt, /// 150 knots < Max speed < 300 knots
185
speed600kt, /// 300 knots < Max speed < 600 knots
186
speed1200kt, /// 600 knots < Max speed < 1200 knots
187
speedGreater /// 1200 knots < Max speed
188
} sg_airspeed_t;
189
190
/**
191
* Available antenna configurations
192
*/
193
typedef enum
194
{
195
antBottom = 1, /// bottom antenna only
196
antBoth = 3 /// both top and bottom antennae
197
} sg_antenna_t;
198
199
/**
200
* The XPNDR Installation Message.
201
* Host --> XPNDR.
202
* XPNDR --> Host.
203
* Use 'strcpy(install.reg, "REGVAL1")' to assign the registration.
204
*/
205
typedef struct
206
{
207
uint32_t icao; /// The aircraft's ICAO address
208
char reg[8]; /// The aircraft's registration (left-justified alphanumeric characters padded with spaces)
209
sg_baud_t com0; /// The baud rate for COM Port 0
210
sg_baud_t com1; /// The baud rate for COM Port 1
211
sg_ethernet_t eth; /// The ethernet configuration
212
sg_sil_t sil; /// The gps integrity SIL parameter
213
sg_sda_t sda; /// The gps integrity SDA parameter
214
sg_emitter_t emitter; /// The platform's emitter type
215
sg_size_t size; /// The platform's dimensions
216
sg_airspeed_t maxSpeed; /// The platform's maximum airspeed
217
int16_t altOffset; /// The altitude encoder offset is a legacy field that should always = 0
218
sg_antenna_t antenna; /// The antenna configuration
219
bool altRes100; /// Altitude resolution. true = 100 foot, false = 25 foot
220
bool hdgTrueNorth; /// Heading type. true = true north, false = magnetic north
221
bool airspeedTrue; /// Airspeed type. true = true speed, false = indicated speed
222
bool heater; /// true = heater enabled, false = heater disabled
223
bool wowConnected; /// Weight on Wheels sensor. true = connected, false = not connected
224
} sg_install_t;
225
226
/**
227
* The XPNDR Flight ID Message.
228
* Host --> XPNDR.
229
* XPNDR --> Host.
230
* * Use 'strcpy(id.flightID, "FLIGHTNO")' to assign the flight identification.
231
*/
232
typedef struct
233
{
234
char flightId[9]; /// The flight identification (left-justified alphanumeric characters padded with spaces)
235
} sg_flightid_t;
236
237
/**
238
* Available transponder operating modes. The enumerated values are
239
* offset from the host message protocol values.
240
*/
241
typedef enum
242
{
243
modeOff = 0, /// 'Off' Mode: Xpdr will not transmit
244
modeOn, /// 'On' Mode: Full functionality with Altitude = Invalid
245
modeStby, /// 'Standby' Mode: Reply to lethal interrogations, only
246
modeAlt /// 'Alt' Mode: Full functionality
247
} sg_op_mode_t;
248
249
/**
250
* Available emergency status codes.
251
*/
252
typedef enum
253
{
254
emergcNone = 0, /// No Emergency
255
emergcGeneral, /// General Emergency
256
emergcMed, /// Lifeguard/Medical Emergency
257
emergcFuel, /// Minimum Fuel
258
emergcComm, /// No Communications
259
emergcIntrfrc, /// Unlawful Interference
260
emergcDowned /// Downed Aircraft
261
} sg_emergc_t;
262
263
/**
264
* The XPNDR Operating Message.
265
* Host --> XPNDR.
266
*/
267
typedef struct
268
{
269
uint16_t squawk; /// 4-digit octal Mode A code
270
sg_op_mode_t opMode; /// Operational mode
271
bool savePowerUp; /// Save power-up state in non-volatile
272
bool enableSqt; /// Enable extended squitters
273
bool enableXBit; /// Enable the x-bit
274
bool milEmergency; /// Broadcast a military emergency
275
sg_emergc_t emergcType; /// Enumerated civilian emergency type
276
bool identOn; /// Set the identification switch = On
277
bool altUseIntrnl; /// True = Report altitude from internal pressure sensor (will ignore other bits in the field)
278
bool altHostAvlbl; /// True = Host Altitude is being provided
279
bool altRes25; /// Host Altitude Resolution from install message, True = 25 ft, False = 100 ft
280
int32_t altitude; /// Sea-level altitude in feet. Field is ignored when internal altitude is selected.
281
bool climbValid; /// Climb rate is provided;
282
int16_t climbRate; /// Climb rate in ft/min. Limits are +/- 16,448 ft/min.
283
bool headingValid; /// Heading is valid.
284
double heading; /// Heading in degrees
285
bool airspdValid; /// Airspeed is valid.
286
uint16_t airspd; /// Airspeed in knots.
287
} sg_operating_t;
288
289
/**
290
* Avaiable NACp values.
291
*/
292
typedef enum
293
{
294
nacpUnknown, /// >= 18.52 km ( 10 nmile)
295
nacp10dot0, /// < 18.52 km ( 10 nmile)
296
nacp4dot0, /// < 7.408 km ( 4 nmile)
297
nacp2dot0, /// < 3.704 km ( 2 nmile)
298
nacp1dot0, /// < 1.852 km ( 1 nmile)
299
nacp0dot5, /// < 0.926 km (0.5 nmile)
300
nacp0dot3, /// < 0.556 km (0.3 nmile)
301
nacp0dot1, /// < 0.185 km (0.1 nmile)
302
nacp0dot05, /// < 92.6 m (0.05 nmile)
303
nacp30, /// < 30.0 m
304
nacp10, /// < 10.0 m
305
nacp3 /// < 3.0 m
306
} sg_nacp_t;
307
308
/**
309
* Available NACv values (m/s)
310
*/
311
typedef enum
312
{
313
nacvUnknown = 0, /// 10 <= NACv (or NACv is unknown)
314
nacv10dot0, /// 3 <= NACv < 10
315
nacv3dot0, /// 1 <= NACv < 3
316
nacv1dot0, /// 0.3 <= NACv < 1
317
nacv0dot3 /// 0.0 <= NACv < 0.3
318
} sg_nacv_t;
319
320
/**
321
* The XPNDR Simulated GPS Message.
322
* Host --> XPNDR.
323
*/
324
typedef struct
325
{
326
char longitude[12]; /// The absolute value of longitude (degree and decimal minute)
327
char latitude[11]; /// The absolute value of latitude (degree and decimal minute)
328
char grdSpeed[7]; /// The GPS over-ground speed (knots)
329
char grdTrack[9]; /// The GPS track referenced from True North (degrees, clockwise)
330
bool latNorth; /// The aircraft is in the northern hemisphere
331
bool lngEast; /// The aircraft is in the eastern hemisphere
332
bool fdeFail; /// True = A satellite error has occurred
333
bool gpsValid; /// True = GPS data is valid
334
char timeOfFix[11]; /// Time, relative to midnight UTC (can optionally be filled spaces)
335
float height; /// The height above the WGS-84 ellipsoid (meters)
336
float hpl; /// The Horizontal Protection Limit (meters)
337
float hfom; /// The Horizontal Figure of Merit (meters)
338
float vfom; /// The Vertical Figure of Merit (meters)
339
sg_nacv_t nacv; /// Navigation Accuracy for Velocity (meters/second)
340
} sg_gps_t;
341
342
/**
343
* Available data request types
344
*/
345
typedef enum
346
{
347
dataInstall = 0x81, /// Installation data
348
dataFlightID = 0x82, /// Flight Identification data
349
dataStatus = 0x83, /// Status Response data
350
dataMode = 0x8C, /// Mode Settings data
351
dataHealth = 0x8D, /// Health Monitor data
352
dataVersion = 0x8E, /// Version data
353
dataSerialNum = 0x8F, /// Serial Number data
354
dataTOD = 0xD2, /// Time of Day data
355
dataMode5 = 0xD3, /// Mode 5 Indication data
356
dataCrypto = 0xD4, /// Crypto Status data
357
dataMilSettings = 0xD7 /// Military Settings data
358
} sg_datatype_t;
359
360
/**
361
* The Data Request message.
362
* Host --> XPDR.
363
*/
364
typedef struct
365
{
366
sg_datatype_t reqType; /// The desired data response
367
uint8_t resv[3];
368
} sg_datareq_t;
369
370
/**
371
* Available target request types
372
*/
373
typedef enum
374
{
375
reportAuto = 0, /// Enable auto output of all target reports
376
reportSummary, /// Report list of all tracked targets (disables auto-output)
377
reportIcao, /// Generate reports for specific target, only (disables auto-output)
378
reportNone /// Disable all target reports
379
} sg_reporttype_t;
380
381
/**
382
* Available target report transmission ports
383
*/
384
typedef enum
385
{
386
transmitSource = 0, /// Transmit reports on channel where target request was received
387
transmitCom0, /// Transmit reports on Com0
388
transmitCom1, /// Transmit reports on Com1
389
transmitEth /// Transmit reports on Ethernet
390
} sg_transmitport_t;
391
392
/**
393
* The Target Request message for ADS-B 'in' data.
394
* Host --> XPDR.
395
*/
396
typedef struct
397
{
398
sg_reporttype_t reqType; /// The desired report mode
399
sg_transmitport_t transmitPort; /// The communication port used for report transmission
400
uint16_t maxTargets; /// The maximum number of targets to track (max value: 404)
401
uint32_t icao; /// The desired target's ID, if applicable
402
bool stateVector; /// Transmit state vector reports
403
bool modeStatus; /// Transmit mode status reports
404
bool targetState; /// Transmit target state reports
405
bool airRefVel; /// Transmit air referenced velocity reports
406
bool tisb; /// Transmit raw TIS-B message reports (requires auto-output)
407
bool military; /// Enable tracking of military aircraft
408
bool commA; /// Transmit Comm-A Reports (requires auto-output)
409
bool ownship; /// Transmit reports about own aircraft
410
} sg_targetreq_t;
411
412
/**
413
* The Mode message.
414
* Host --> XPDR.
415
*/
416
typedef struct
417
{
418
bool reboot; /// Reboot the MX
419
} sg_mode_t;
420
421
/**
422
* The XPNDR Acknowledge Message following all host messages.
423
* XPNDR --> Host.
424
*/
425
typedef struct
426
{
427
uint8_t ackType; /// Message type being acknowledged
428
uint8_t ackId; /// Message ID being acknowledged
429
bool failXpdr; /// Built-in-test failure
430
bool failSystem; /// Required system input missing
431
bool failCrypto; /// Crypto status failure
432
bool wow; /// Weight-on-wheels indicates aircraft is on-ground
433
bool maint; /// Maintenance mode enabled
434
bool isHostAlt; /// False = Pressure sensor altitude, True = Host provided value
435
sg_op_mode_t opMode; /// Operational mode
436
int32_t alt; /// Altitude (feet)
437
bool altValid; /// Altitude is valid
438
} sg_ack_t;
439
440
/**
441
* The XPNDR Status Response Message following a Data Request for Status.
442
* XPNDR --> Host.
443
*/
444
typedef struct
445
{
446
uint8_t versionSW; /// SW Version # installed on the XPNDR
447
uint8_t versionFW; /// FW Version # installed on the XPNDR
448
uint32_t crc; /// CRC Checksum for the installed XPNDR SW/FW versions
449
450
bool powerUp : 1; /// Integrity of CPU and Non-Volatile data at power-up
451
bool continuous : 1; /// Set by any other B.I.T. failures during operation
452
bool processor : 1; /// One-time processor instruction set test at power-up
453
bool crcValid : 1; /// Calculate then verifies the CRC against the stored value
454
bool memory : 1; /// Processor RAM is functional
455
bool calibrated : 1; /// Transponder is calibrated
456
bool receiver : 1; /// RF signals travel through hardware correctly
457
bool power53v : 1; /// Voltage at the 53V power supply is correct
458
bool adc : 1; /// Analog-to-Digital Converter is functional
459
bool pressure : 1; /// Internal pressure transducer is functional
460
bool fpga : 1; /// FPGA I/O operations are functional
461
bool rxLock : 1; /// Rx oscillator reporting PLL Lock at reference frequency
462
bool txLock : 1; /// Tx oscillator reporting PLL Lock at reference frequency
463
bool mtSuppress : 1; /// Mutual suppression is operating correctly
464
bool temp : 1; /// Internal temperature is within range (< 110 C)
465
bool sqMonitor : 1; /// Squitters are transmitting at their nominal rates
466
bool txRate : 1; /// Transmission duty cycle is in the safe range
467
bool sysLatency : 1; /// Systems events occurred within expected time limits
468
bool txPower : 1; /// Transmission power is in-range
469
bool voltageIn : 1; /// Input voltage is in-range (10V-32V)
470
bool icao : 1; /// ICAO Address is valid (fail at '000000' or 'FFFFFF')
471
bool gps : 1; /// Valid GPS data is received at 1Hz, minimum
472
} sg_status_t;
473
474
/**
475
* The XPNDR Health Monitor Response Message.
476
* XPNDR --> Host.
477
*/
478
typedef struct
479
{
480
int8_t socTemp; /// System on a Chip temperature
481
int8_t rfTemp; /// RF Board temperature
482
int8_t ptTemp; /// Pressure Transducer temperature
483
} sg_healthmonitor_t;
484
485
/**
486
* The XPNDR Version Response Message.
487
* XPNDR --> Host.
488
*/
489
typedef struct
490
{
491
uint8_t swVersion; /// The SW Version major revision number
492
uint8_t fwVersion; /// The FW Version major revision number
493
uint16_t swSvnRevision; /// The SW Repository version number
494
uint16_t fwSvnRevision; /// The FW Repository version number
495
} sg_version_t;
496
497
/**
498
* The XPNDR Serial Number Response Message.
499
* XPNDR --> Host.
500
*/
501
typedef struct
502
{
503
char ifSN[33]; /// The Interface Board serial number
504
char rfSN[33]; /// The RF Board serial number
505
char xpndrSN[33]; /// The Transponder serial number
506
} sg_serialnumber_t;
507
508
/// The state vector report type.
509
typedef enum
510
{
511
svrAirborne = 1, /// Airborne state vector report type.
512
svrSurface /// Surface state vector report type.
513
} sg_svr_type_t;
514
515
/// The state vector report participant address type.
516
typedef enum
517
{
518
svrAdrIcaoUnknown, /// ICAO address unknown emitter category.
519
svrAdrNonIcaoUnknown, /// Non-ICAO address unknown emitter category.
520
svrAdrIcao, /// ICAO address aircraft.
521
svrAdrNonIcao, /// Non-ICAO address aircraft.
522
svrAdrIcaoSurface, /// ICAO address surface vehicle, fixed ground, tethered obstruction.
523
svrAdrNonIcaoSurface, /// Non-ICAO address surface vehicle, fixed ground, tethered obstruction.
524
svrAdrDup, /// Duplicate target of another ICAO address.
525
svrAdrAdsr /// ADS-R target.
526
} sg_addr_type_t;
527
528
/// The surface part of a state vector report.
529
typedef struct
530
{
531
int16_t speed; /// Surface speed.
532
int16_t heading; /// Surface heading.
533
} sg_svr_surface_t;
534
535
/// The airborne part of a state vector report.
536
typedef struct
537
{
538
int16_t velNS; /// The NS speed vector component. [knots]
539
int16_t velEW; /// The EW speed vector component. [knots]
540
int16_t speed; /// Speed from N/S and E/W velocity. [knots]
541
int16_t heading; /// Heading from N/S and E/W velocity. [deg from N]
542
int32_t geoAlt; /// Geometric altitude. [ft]
543
int32_t baroAlt; /// Barometric altitude. [ft]
544
int16_t vrate; /// Vertical rate. [ft/min]
545
float estLat; /// Estimated latitude. [deg N]
546
float estLon; /// Estimated longitude. [deg E]
547
} sg_svr_airborne_t;
548
549
typedef struct
550
{
551
bool baroVRate : 1; /// Barometric vertical rate valid.
552
bool geoVRate : 1; /// Geometric vertical rate valid.
553
bool baroAlt : 1; /// Barometric altitude valid.
554
bool surfHeading : 1; /// Surface heading valid.
555
bool surfSpeed : 1; /// Surface speed valid.
556
bool airSpeed : 1; /// Airborne speed and heading valid.
557
bool geoAlt : 1; /// Geometric altitude valid.
558
bool position : 1; /// Lat and lon data valid.
559
} sg_svr_validity_t;
560
561
typedef struct
562
{
563
uint8_t reserved : 6; /// Reserved.
564
bool estSpeed : 1; /// Estimated N/S and E/W velocity.
565
bool estPosition : 1; /// Estimated lat/lon position.
566
} sg_svr_est_validity_t;
567
568
/**
569
* The XPDR ADS-B state vector report Message.
570
* Host --> XPDR.
571
*
572
* @note The time of applicability values are based on the MX system clock that starts
573
* at 0 on power up. The time is the floating point number that is the seconds since
574
* power up. The time number rolls over at 512.0.
575
*/
576
typedef struct
577
{
578
sg_svr_type_t type; /// Report type.
579
union
580
{
581
uint8_t flags;
582
sg_svr_validity_t validity; /// Field validity flags.
583
};
584
union
585
{
586
uint8_t eflags;
587
sg_svr_est_validity_t evalidity; /// Estimated field validity flags.
588
};
589
uint32_t addr; /// Participant address.
590
sg_addr_type_t addrType; /// Participant address type.
591
float toaEst; /// Report estimated position and speed time of applicability.
592
float toaPosition; /// Report position time of applicability.
593
float toaSpeed; /// Report speed time of applicability.
594
uint8_t survStatus; /// Surveillance status.
595
uint8_t mode; /// Report mode.
596
uint8_t nic; /// Navigation integrity category.
597
float lat; /// Latitude.
598
float lon; /// Longitude.
599
union
600
{
601
sg_svr_surface_t surface; /// Surface SVR data.
602
sg_svr_airborne_t airborne; /// Airborne SVR data.
603
};
604
} sg_svr_t;
605
606
typedef enum
607
{
608
msrTypeV0,
609
msrTypeV1Airborne,
610
msrTypeV1Surface,
611
msrTypeV2Airborne,
612
msrTypeV2Surface
613
} sg_msr_type_t;
614
615
typedef struct
616
{
617
uint8_t reserved : 2;
618
bool priority : 1;
619
bool sil : 1;
620
bool nacv : 1;
621
bool nacp : 1;
622
bool opmode : 1;
623
bool capcodes : 1;
624
} sg_msr_validity_t;
625
626
typedef enum
627
{
628
adsbVerDO260,
629
adsbVerDO260A,
630
adsbVerDO260B
631
} sg_adsb_version_t;
632
633
typedef enum
634
{
635
adsbUnknown,
636
adsbLight,
637
adsbSmall = 0x3,
638
adsbLarge = 0x5,
639
adsbHighVortex,
640
adsbHeavy,
641
adsbPerformance,
642
adsbRotorcraft = 0x0A,
643
adsbGlider,
644
adsbAir,
645
adsbUnmaned,
646
adsbSpace,
647
adsbUltralight,
648
adsbParachutist,
649
adsbVehicle_emg = 0x14,
650
adsbVehicle_serv,
651
adsbObsticlePoint,
652
adsbObsticleCluster,
653
adsbObsticleLinear
654
} sg_adsb_emitter_t;
655
656
typedef enum
657
{
658
priNone,
659
priGeneral,
660
priMedical,
661
priFuel,
662
priComm,
663
priUnlawful,
664
priDowned
665
} sg_priority_t;
666
667
typedef enum
668
{
669
tcrNone,
670
tcrSingle,
671
tcrMultiple
672
} sg_tcr_t;
673
674
typedef struct
675
{
676
bool b2low : 1;
677
bool uat : 1;
678
bool arv : 1;
679
bool tsr : 1;
680
bool adsb : 1;
681
bool tcas : 1;
682
sg_tcr_t tcr;
683
} sg_capability_t;
684
685
typedef enum
686
{
687
gpsLonNodata,
688
gpsLonSensorSupplied,
689
gpsLon2m,
690
gpsLon4m,
691
gpsLon6m,
692
gpsLon8m,
693
gpsLon10m,
694
gpsLon12m,
695
gpsLon14m,
696
gpsLon16m,
697
gpsLon18m,
698
gpsLon20m,
699
gpsLon22m,
700
gpsLon24m,
701
gpsLon26m,
702
gpsLon28m,
703
gpsLon30m,
704
gpsLon32m,
705
gpsLon34m,
706
gpsLon36m,
707
gpsLon38m,
708
gpsLon40m,
709
gpsLon42m,
710
gpsLon44m,
711
gpsLon46m,
712
gpsLon48m,
713
gpsLon50m,
714
gpsLon52m,
715
gpsLon54m,
716
gpsLon56m,
717
gpsLon58m,
718
gpsLon60m
719
} sg_gps_lonofs_t;
720
721
typedef enum
722
{
723
gpslatNodata,
724
gpslatLeft2m,
725
gpslatLeft4m,
726
gpslatLeft6m,
727
gpslatRight0m,
728
gpslatRight2m,
729
gpslatRight4m,
730
gpslatRight6m,
731
} sg_gps_latofs_t;
732
733
typedef struct
734
{
735
bool gpsLatFmt;
736
sg_gps_latofs_t gpsLatOfs;
737
bool gpsLonFmt;
738
sg_gps_lonofs_t gpsLonOfs;
739
bool tcasRA : 1;
740
bool ident : 1;
741
bool singleAnt : 1;
742
} sg_adsb_opmode_t;
743
744
typedef enum
745
{
746
gvaUnknown,
747
gvaLT150m,
748
gvaLT45m
749
} sg_gva_t;
750
751
typedef enum
752
{
753
nicGolham,
754
nicNonGilham
755
} sg_nicbaro_t;
756
757
typedef enum
758
{
759
svsilUnknown,
760
svsilPow3,
761
svsilPow5,
762
svsilPow7
763
} sg_svsil_t;
764
765
typedef struct
766
{
767
sg_nacp_t nacp;
768
sg_nacv_t nacv;
769
sg_sda_t sda;
770
bool silSupp;
771
sg_svsil_t sil;
772
sg_gva_t gva;
773
sg_nicbaro_t nicBaro;
774
} sg_sv_qual_t;
775
776
typedef enum
777
{
778
trackTrueNorth,
779
trackMagNorth,
780
headingTrueNorth,
781
headingMagNorth
782
} sg_trackheading_t;
783
784
typedef enum
785
{
786
vrateBaroAlt,
787
vrateGeoAlt
788
} sg_vratetype_t;
789
790
/**
791
* The XPDR ADS-B mode status report Message.
792
* Host --> XPDR.
793
*
794
* @note The time of applicability values are based on the MX system clock that starts
795
* at 0 on power up. The time is the floating point number that is the seconds since
796
* power up. The time number rolls over at 512.0.
797
*/
798
typedef struct
799
{
800
sg_msr_type_t type; /// Report type.
801
802
union
803
{
804
uint8_t flags;
805
sg_msr_validity_t validity; /// Field validity flags.
806
};
807
808
uint32_t addr; /// Participant address.
809
sg_addr_type_t addrType; /// Participant address type.
810
811
float toa;
812
sg_adsb_version_t version;
813
char callsign[9];
814
sg_adsb_emitter_t emitter;
815
sg_size_t size;
816
sg_priority_t priority;
817
sg_capability_t capability;
818
sg_adsb_opmode_t opMode;
819
sg_sv_qual_t svQuality;
820
sg_trackheading_t trackHeading;
821
sg_vratetype_t vrateType;
822
} sg_msr_t;
823
824
/**
825
* Convert install message struct to the raw buffer format.
826
*
827
* @param[out] buffer An empty buffer to contain the raw install message.
828
* @param[in] stl The install message struct with fields populated.
829
* @param[in] msgId The sequence number for the message.
830
*
831
* @return true if successful or false on failure.
832
*
833
* @warning data in stl parameter must be pre-validated.
834
*/
835
bool sgEncodeInstall(uint8_t *buffer, sg_install_t *stl, uint8_t msgId);
836
837
/**
838
* Convert flight identification struct to the raw buffer format.
839
*
840
* @param[out] buffer An empty buffer to contain the raw flight identification message.
841
* @param[in] id The flight id struct with fields populated.
842
* @param[in] msgId The sequence number for the message.
843
*
844
* @return true if successful or false on failure.
845
*
846
* @warning data in id parameter must be pre-validated.
847
*/
848
bool sgEncodeFlightId(uint8_t *buffer, sg_flightid_t *id, uint8_t msgId);
849
850
/**
851
* Convert operating message struct to the raw buffer format.
852
*
853
* @param[out] buffer An empty buffer to contain the raw operating message.
854
* @param[in] op The operating message struct with fields populated.
855
* @param[in] msgId The sequence number for the message.
856
*
857
* @return true if successful or false on failure.
858
*
859
* @warning data in op parameter must be pre-validated.
860
*/
861
bool sgEncodeOperating(uint8_t *buffer, sg_operating_t *op, uint8_t msgId);
862
863
/* TODO: Create GPS helper functions to convert other data types --> char buffers */
864
865
/**
866
* Convert GPS message struct to the raw buffer format.
867
*
868
* @param[out] buffer An empty buffer to contain the raw GPS message.
869
* @param[in] gps The GPS message struct with fields populated.
870
* @param[in] msgId The sequence number for the message.
871
*
872
* @return true if successful or false on failure.
873
*
874
* @warning data in gps parameter must be pre-validated.
875
*/
876
bool sgEncodeGPS(uint8_t *buffer, sg_gps_t *gps, uint8_t msgId);
877
878
/**
879
* Convert data request message struct to the raw buffer format.
880
*
881
* @param[out] buffer An empty buffer to contain the raw target request message.
882
* @param[in] data The data request message struct with fields populated.
883
* @param[in] msgId The sequence number for the message.
884
*
885
* @return true if successful or false on failure.
886
*
887
* @warning data in data parameter must be pre-validated.
888
*/
889
bool sgEncodeDataReq(uint8_t *buffer, sg_datareq_t *data, uint8_t msgId);
890
891
/**
892
* Convert target request message struct to the raw buffer format.
893
*
894
* @param[out] buffer An empty buffer to contain the raw target request message.
895
* @param[in] tgt The target request message struct with fields populated.
896
* @param[in] msgId The sequence number for the message.
897
*
898
* @return true if successful or false on failure.
899
*
900
* @warning data in tgt parameter must be pre-validated.
901
*/
902
bool sgEncodeTargetReq(uint8_t *buffer, sg_targetreq_t *tgt, uint8_t msgId);
903
904
/**
905
* Process the ACK message response from the transponder.
906
*
907
* @param[in] buffer The raw ACK message buffer.
908
* @param[out] ack The parsed message results.
909
*
910
* @return true if successful or false on failure.
911
*/
912
bool sgDecodeAck(uint8_t *buffer, sg_ack_t *ack);
913
914
/**
915
* Process the Install message response from the transponder.
916
*
917
* @param[in] buffer The raw Install message buffer.
918
* @param[out] stl The parsed message results.
919
*
920
* @return true if successful or false on failure.
921
*/
922
bool sgDecodeInstall(uint8_t *buffer, sg_install_t *stl);
923
924
/**
925
* Process the Flight ID message response from the transponder.
926
*
927
* @param[in] buffer The raw Flight ID message buffer.
928
* @param[out] id The parsed message results.
929
*
930
* @return true if successful or false on failure.
931
*/
932
bool sgDecodeFlightId(uint8_t *buffer, sg_flightid_t *id);
933
934
/**
935
* Process the state vector report message.
936
*
937
* @param[in] buffer The raw SVR message buffer.
938
* @param[out] svr The parsed SVR message.
939
*
940
* @return true if successful or false on failure.
941
*/
942
bool sgDecodeSVR(uint8_t *buffer, sg_svr_t *svr);
943
944
/**
945
* Process the mode status report message.
946
*
947
* @param buffer The raw MSR message buffer.
948
* @param msr The parsed MSR message.
949
*
950
* @return true if successful or false on failure.
951
*/
952
bool sgDecodeMSR(uint8_t *buffer, sg_msr_t *msr);
953
954
#endif /* SG_H */
955
956