Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_ADSB/sagetech-sdk/sg.h
Views: 1799
/**1* @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved.2*3* @file sg.h4* @author jimb5*6* @date Feb 10, 20217*8* Sagetech protocol for host message building and parsing.9*10* This module performs both the following:11* 1. Parses raw Sagetech host messages defined in the SDIM and12* returns a populated struct dataset of the message type.13* 2. Receives a populated struct dataset of the desired host message14* and returns the corresponding raw message data buffer.15*/1617#ifndef SG_H18#define SG_H1920#include <stdint.h>21#include <stdbool.h>2223/// Host Message Lengths (bytes)24#define SG_MSG_LEN_INSTALL 4125#define SG_MSG_LEN_FLIGHT 1726#define SG_MSG_LEN_OPMSG 1727#define SG_MSG_LEN_GPS 6828#define SG_MSG_LEN_DATAREQ 929#define SG_MSG_LEN_TARGETREQ 1230#define SG_MSG_LEN_MODE 103132/// Host Message Types33#define SG_MSG_TYPE_HOST_INSTALL 0x0134#define SG_MSG_TYPE_HOST_FLIGHT 0x0235#define SG_MSG_TYPE_HOST_OPMSG 0x0336#define SG_MSG_TYPE_HOST_GPS 0x0437#define SG_MSG_TYPE_HOST_DATAREQ 0x0538#define SG_MSG_TYPE_HOST_TARGETREQ 0x0B39#define SG_MSG_TYPE_HOST_MODE 0x0C4041/// XPNDR Message Types42#define SG_MSG_TYPE_XPNDR_ACK 0x8043#define SG_MSG_TYPE_XPNDR_INSTALL 0x8144#define SG_MSG_TYPE_XPNDR_FLIGHT 0x8245#define SG_MSG_TYPE_XPNDR_STATUS 0x8346#define SG_MSG_TYPE_XPNDR_COMMA 0x8547#define SG_MSG_TYPE_XPNDR_MODE 0x8C48#define SG_MSG_TYPE_XPNDR_VERSION 0x8E49#define SG_MSG_TYPE_XPNDR_SERIALNUM 0x8F5051/// ADS-B Message Types52#define SG_MSG_TYPE_ADSB_TSUMMARY 0x9053#define SG_MSG_TYPE_ADSB_SVR 0x9154#define SG_MSG_TYPE_ADSB_MSR 0x9255#define SG_MSG_TYPE_ADSB_TSTATE 0x9756#define SG_MSG_TYPE_ADSB_ARVR 0x985758/// Start byte for all host messages59#define SG_MSG_START_BYTE 0xAA6061/// Emitter category set byte values62#define SG_EMIT_GROUP_A 0x0063#define SG_EMIT_GROUP_B 0x0164#define SG_EMIT_GROUP_C 0x0265#define SG_EMIT_GROUP_D 0x036667/// Emitter category enumeration offsets68#define SG_EMIT_OFFSET_A 0x0069#define SG_EMIT_OFFSET_B 0x1070#define SG_EMIT_OFFSET_C 0x2071#define SG_EMIT_OFFSET_D 0x307273/**74* Available COM port baud rates.75*/76typedef enum77{78baud38400 = 0,79baud600,80baud4800,81baud9600,82baud28800,83baud57600,84baud115200,85baud230400,86baud19200,87baud460800,88baud92160089} sg_baud_t;9091/**92* Transponder ethernet configuration93*/94typedef struct95{96uint32_t ipAddress; /// The transponder ip address97uint32_t subnetMask; /// The transponder subnet mask98uint16_t portNumber; /// The transponder port number99} sg_ethernet_t;100101/**102* Available GPS integrity SIL values103*/104typedef enum105{106silUnknown = 0,107silLow,108silMedium,109silHigh110} sg_sil_t;111112/**113* Available GPS integrity SDA values114*/115typedef enum116{117sdaUnknown = 0,118sdaMinor,119sdaMajor,120sdaHazardous121} sg_sda_t;122123/**124* Available emitter types125*/126typedef enum127{128aUnknown = SG_EMIT_OFFSET_A,129aLight,130aSmall,131aLarge,132aHighVortex,133aHeavy,134aPerformance,135aRotorCraft,136bUnknown = SG_EMIT_OFFSET_B,137bGlider,138bAir,139bParachutist,140bUltralight,141bUAV = SG_EMIT_OFFSET_B + 6,142bSpace,143cUnknown = SG_EMIT_OFFSET_C,144cEmergency,145cService,146cPoint,147cCluster,148cLine,149dUnknown = SG_EMIT_OFFSET_D150} sg_emitter_t;151152/**153* Available aircraft sizes in meters154*/155typedef enum156{157sizeUnknown = 0, /// Dimensions unknown158sizeL15W23, /// Length <= 15m & Width <= 23m159sizeL25W28, /// Length <= 25m & Width <= 28.5m160sizeL25W34, /// Length <= 25m & Width <= 34m161sizeL35W33, /// Length <= 35m & Width <= 33m162sizeL35W38, /// Length <= 35m & Width <= 38m163sizeL45W39, /// Length <= 45m & Width <= 39.5m164sizeL45W45, /// Length <= 45m & Width <= 45m165sizeL55W45, /// Length <= 55m & Width <= 45m166sizeL55W52, /// Length <= 55m & Width <= 52m167sizeL65W59, /// Length <= 65m & Width <= 59.5m168sizeL65W67, /// Length <= 65m & Width <= 67m169sizeL75W72, /// Length <= 75m & Width <= 72.5m170sizeL75W80, /// Length <= 75m & Width <= 80m171sizeL85W80, /// Length <= 85m & Width <= 80m172sizeL85W90 /// Length <= 85m & Width <= 90m173} sg_size_t;174175/**176* Available aircraft maximum airspeeds177*/178typedef enum179{180speedUnknown = 0, /// Max speed unknown181speed75kt, /// 0 knots < Max speed < 75 knots182speed150kt, /// 75 knots < Max speed < 150 knots183speed300kt, /// 150 knots < Max speed < 300 knots184speed600kt, /// 300 knots < Max speed < 600 knots185speed1200kt, /// 600 knots < Max speed < 1200 knots186speedGreater /// 1200 knots < Max speed187} sg_airspeed_t;188189/**190* Available antenna configurations191*/192typedef enum193{194antBottom = 1, /// bottom antenna only195antBoth = 3 /// both top and bottom antennae196} sg_antenna_t;197198/**199* The XPNDR Installation Message.200* Host --> XPNDR.201* XPNDR --> Host.202* Use 'strcpy(install.reg, "REGVAL1")' to assign the registration.203*/204typedef struct205{206uint32_t icao; /// The aircraft's ICAO address207char reg[8]; /// The aircraft's registration (left-justified alphanumeric characters padded with spaces)208sg_baud_t com0; /// The baud rate for COM Port 0209sg_baud_t com1; /// The baud rate for COM Port 1210sg_ethernet_t eth; /// The ethernet configuration211sg_sil_t sil; /// The gps integrity SIL parameter212sg_sda_t sda; /// The gps integrity SDA parameter213sg_emitter_t emitter; /// The platform's emitter type214sg_size_t size; /// The platform's dimensions215sg_airspeed_t maxSpeed; /// The platform's maximum airspeed216int16_t altOffset; /// The altitude encoder offset is a legacy field that should always = 0217sg_antenna_t antenna; /// The antenna configuration218bool altRes100; /// Altitude resolution. true = 100 foot, false = 25 foot219bool hdgTrueNorth; /// Heading type. true = true north, false = magnetic north220bool airspeedTrue; /// Airspeed type. true = true speed, false = indicated speed221bool heater; /// true = heater enabled, false = heater disabled222bool wowConnected; /// Weight on Wheels sensor. true = connected, false = not connected223} sg_install_t;224225/**226* The XPNDR Flight ID Message.227* Host --> XPNDR.228* XPNDR --> Host.229* * Use 'strcpy(id.flightID, "FLIGHTNO")' to assign the flight identification.230*/231typedef struct232{233char flightId[9]; /// The flight identification (left-justified alphanumeric characters padded with spaces)234} sg_flightid_t;235236/**237* Available transponder operating modes. The enumerated values are238* offset from the host message protocol values.239*/240typedef enum241{242modeOff = 0, /// 'Off' Mode: Xpdr will not transmit243modeOn, /// 'On' Mode: Full functionality with Altitude = Invalid244modeStby, /// 'Standby' Mode: Reply to lethal interrogations, only245modeAlt /// 'Alt' Mode: Full functionality246} sg_op_mode_t;247248/**249* Available emergency status codes.250*/251typedef enum252{253emergcNone = 0, /// No Emergency254emergcGeneral, /// General Emergency255emergcMed, /// Lifeguard/Medical Emergency256emergcFuel, /// Minimum Fuel257emergcComm, /// No Communications258emergcIntrfrc, /// Unlawful Interference259emergcDowned /// Downed Aircraft260} sg_emergc_t;261262/**263* The XPNDR Operating Message.264* Host --> XPNDR.265*/266typedef struct267{268uint16_t squawk; /// 4-digit octal Mode A code269sg_op_mode_t opMode; /// Operational mode270bool savePowerUp; /// Save power-up state in non-volatile271bool enableSqt; /// Enable extended squitters272bool enableXBit; /// Enable the x-bit273bool milEmergency; /// Broadcast a military emergency274sg_emergc_t emergcType; /// Enumerated civilian emergency type275bool identOn; /// Set the identification switch = On276bool altUseIntrnl; /// True = Report altitude from internal pressure sensor (will ignore other bits in the field)277bool altHostAvlbl; /// True = Host Altitude is being provided278bool altRes25; /// Host Altitude Resolution from install message, True = 25 ft, False = 100 ft279int32_t altitude; /// Sea-level altitude in feet. Field is ignored when internal altitude is selected.280bool climbValid; /// Climb rate is provided;281int16_t climbRate; /// Climb rate in ft/min. Limits are +/- 16,448 ft/min.282bool headingValid; /// Heading is valid.283double heading; /// Heading in degrees284bool airspdValid; /// Airspeed is valid.285uint16_t airspd; /// Airspeed in knots.286} sg_operating_t;287288/**289* Avaiable NACp values.290*/291typedef enum292{293nacpUnknown, /// >= 18.52 km ( 10 nmile)294nacp10dot0, /// < 18.52 km ( 10 nmile)295nacp4dot0, /// < 7.408 km ( 4 nmile)296nacp2dot0, /// < 3.704 km ( 2 nmile)297nacp1dot0, /// < 1.852 km ( 1 nmile)298nacp0dot5, /// < 0.926 km (0.5 nmile)299nacp0dot3, /// < 0.556 km (0.3 nmile)300nacp0dot1, /// < 0.185 km (0.1 nmile)301nacp0dot05, /// < 92.6 m (0.05 nmile)302nacp30, /// < 30.0 m303nacp10, /// < 10.0 m304nacp3 /// < 3.0 m305} sg_nacp_t;306307/**308* Available NACv values (m/s)309*/310typedef enum311{312nacvUnknown = 0, /// 10 <= NACv (or NACv is unknown)313nacv10dot0, /// 3 <= NACv < 10314nacv3dot0, /// 1 <= NACv < 3315nacv1dot0, /// 0.3 <= NACv < 1316nacv0dot3 /// 0.0 <= NACv < 0.3317} sg_nacv_t;318319/**320* The XPNDR Simulated GPS Message.321* Host --> XPNDR.322*/323typedef struct324{325char longitude[12]; /// The absolute value of longitude (degree and decimal minute)326char latitude[11]; /// The absolute value of latitude (degree and decimal minute)327char grdSpeed[7]; /// The GPS over-ground speed (knots)328char grdTrack[9]; /// The GPS track referenced from True North (degrees, clockwise)329bool latNorth; /// The aircraft is in the northern hemisphere330bool lngEast; /// The aircraft is in the eastern hemisphere331bool fdeFail; /// True = A satellite error has occurred332bool gpsValid; /// True = GPS data is valid333char timeOfFix[11]; /// Time, relative to midnight UTC (can optionally be filled spaces)334float height; /// The height above the WGS-84 ellipsoid (meters)335float hpl; /// The Horizontal Protection Limit (meters)336float hfom; /// The Horizontal Figure of Merit (meters)337float vfom; /// The Vertical Figure of Merit (meters)338sg_nacv_t nacv; /// Navigation Accuracy for Velocity (meters/second)339} sg_gps_t;340341/**342* Available data request types343*/344typedef enum345{346dataInstall = 0x81, /// Installation data347dataFlightID = 0x82, /// Flight Identification data348dataStatus = 0x83, /// Status Response data349dataMode = 0x8C, /// Mode Settings data350dataHealth = 0x8D, /// Health Monitor data351dataVersion = 0x8E, /// Version data352dataSerialNum = 0x8F, /// Serial Number data353dataTOD = 0xD2, /// Time of Day data354dataMode5 = 0xD3, /// Mode 5 Indication data355dataCrypto = 0xD4, /// Crypto Status data356dataMilSettings = 0xD7 /// Military Settings data357} sg_datatype_t;358359/**360* The Data Request message.361* Host --> XPDR.362*/363typedef struct364{365sg_datatype_t reqType; /// The desired data response366uint8_t resv[3];367} sg_datareq_t;368369/**370* Available target request types371*/372typedef enum373{374reportAuto = 0, /// Enable auto output of all target reports375reportSummary, /// Report list of all tracked targets (disables auto-output)376reportIcao, /// Generate reports for specific target, only (disables auto-output)377reportNone /// Disable all target reports378} sg_reporttype_t;379380/**381* Available target report transmission ports382*/383typedef enum384{385transmitSource = 0, /// Transmit reports on channel where target request was received386transmitCom0, /// Transmit reports on Com0387transmitCom1, /// Transmit reports on Com1388transmitEth /// Transmit reports on Ethernet389} sg_transmitport_t;390391/**392* The Target Request message for ADS-B 'in' data.393* Host --> XPDR.394*/395typedef struct396{397sg_reporttype_t reqType; /// The desired report mode398sg_transmitport_t transmitPort; /// The communication port used for report transmission399uint16_t maxTargets; /// The maximum number of targets to track (max value: 404)400uint32_t icao; /// The desired target's ID, if applicable401bool stateVector; /// Transmit state vector reports402bool modeStatus; /// Transmit mode status reports403bool targetState; /// Transmit target state reports404bool airRefVel; /// Transmit air referenced velocity reports405bool tisb; /// Transmit raw TIS-B message reports (requires auto-output)406bool military; /// Enable tracking of military aircraft407bool commA; /// Transmit Comm-A Reports (requires auto-output)408bool ownship; /// Transmit reports about own aircraft409} sg_targetreq_t;410411/**412* The Mode message.413* Host --> XPDR.414*/415typedef struct416{417bool reboot; /// Reboot the MX418} sg_mode_t;419420/**421* The XPNDR Acknowledge Message following all host messages.422* XPNDR --> Host.423*/424typedef struct425{426uint8_t ackType; /// Message type being acknowledged427uint8_t ackId; /// Message ID being acknowledged428bool failXpdr; /// Built-in-test failure429bool failSystem; /// Required system input missing430bool failCrypto; /// Crypto status failure431bool wow; /// Weight-on-wheels indicates aircraft is on-ground432bool maint; /// Maintenance mode enabled433bool isHostAlt; /// False = Pressure sensor altitude, True = Host provided value434sg_op_mode_t opMode; /// Operational mode435int32_t alt; /// Altitude (feet)436bool altValid; /// Altitude is valid437} sg_ack_t;438439/**440* The XPNDR Status Response Message following a Data Request for Status.441* XPNDR --> Host.442*/443typedef struct444{445uint8_t versionSW; /// SW Version # installed on the XPNDR446uint8_t versionFW; /// FW Version # installed on the XPNDR447uint32_t crc; /// CRC Checksum for the installed XPNDR SW/FW versions448449bool powerUp : 1; /// Integrity of CPU and Non-Volatile data at power-up450bool continuous : 1; /// Set by any other B.I.T. failures during operation451bool processor : 1; /// One-time processor instruction set test at power-up452bool crcValid : 1; /// Calculate then verifies the CRC against the stored value453bool memory : 1; /// Processor RAM is functional454bool calibrated : 1; /// Transponder is calibrated455bool receiver : 1; /// RF signals travel through hardware correctly456bool power53v : 1; /// Voltage at the 53V power supply is correct457bool adc : 1; /// Analog-to-Digital Converter is functional458bool pressure : 1; /// Internal pressure transducer is functional459bool fpga : 1; /// FPGA I/O operations are functional460bool rxLock : 1; /// Rx oscillator reporting PLL Lock at reference frequency461bool txLock : 1; /// Tx oscillator reporting PLL Lock at reference frequency462bool mtSuppress : 1; /// Mutual suppression is operating correctly463bool temp : 1; /// Internal temperature is within range (< 110 C)464bool sqMonitor : 1; /// Squitters are transmitting at their nominal rates465bool txRate : 1; /// Transmission duty cycle is in the safe range466bool sysLatency : 1; /// Systems events occurred within expected time limits467bool txPower : 1; /// Transmission power is in-range468bool voltageIn : 1; /// Input voltage is in-range (10V-32V)469bool icao : 1; /// ICAO Address is valid (fail at '000000' or 'FFFFFF')470bool gps : 1; /// Valid GPS data is received at 1Hz, minimum471} sg_status_t;472473/**474* The XPNDR Health Monitor Response Message.475* XPNDR --> Host.476*/477typedef struct478{479int8_t socTemp; /// System on a Chip temperature480int8_t rfTemp; /// RF Board temperature481int8_t ptTemp; /// Pressure Transducer temperature482} sg_healthmonitor_t;483484/**485* The XPNDR Version Response Message.486* XPNDR --> Host.487*/488typedef struct489{490uint8_t swVersion; /// The SW Version major revision number491uint8_t fwVersion; /// The FW Version major revision number492uint16_t swSvnRevision; /// The SW Repository version number493uint16_t fwSvnRevision; /// The FW Repository version number494} sg_version_t;495496/**497* The XPNDR Serial Number Response Message.498* XPNDR --> Host.499*/500typedef struct501{502char ifSN[33]; /// The Interface Board serial number503char rfSN[33]; /// The RF Board serial number504char xpndrSN[33]; /// The Transponder serial number505} sg_serialnumber_t;506507/// The state vector report type.508typedef enum509{510svrAirborne = 1, /// Airborne state vector report type.511svrSurface /// Surface state vector report type.512} sg_svr_type_t;513514/// The state vector report participant address type.515typedef enum516{517svrAdrIcaoUnknown, /// ICAO address unknown emitter category.518svrAdrNonIcaoUnknown, /// Non-ICAO address unknown emitter category.519svrAdrIcao, /// ICAO address aircraft.520svrAdrNonIcao, /// Non-ICAO address aircraft.521svrAdrIcaoSurface, /// ICAO address surface vehicle, fixed ground, tethered obstruction.522svrAdrNonIcaoSurface, /// Non-ICAO address surface vehicle, fixed ground, tethered obstruction.523svrAdrDup, /// Duplicate target of another ICAO address.524svrAdrAdsr /// ADS-R target.525} sg_addr_type_t;526527/// The surface part of a state vector report.528typedef struct529{530int16_t speed; /// Surface speed.531int16_t heading; /// Surface heading.532} sg_svr_surface_t;533534/// The airborne part of a state vector report.535typedef struct536{537int16_t velNS; /// The NS speed vector component. [knots]538int16_t velEW; /// The EW speed vector component. [knots]539int16_t speed; /// Speed from N/S and E/W velocity. [knots]540int16_t heading; /// Heading from N/S and E/W velocity. [deg from N]541int32_t geoAlt; /// Geometric altitude. [ft]542int32_t baroAlt; /// Barometric altitude. [ft]543int16_t vrate; /// Vertical rate. [ft/min]544float estLat; /// Estimated latitude. [deg N]545float estLon; /// Estimated longitude. [deg E]546} sg_svr_airborne_t;547548typedef struct549{550bool baroVRate : 1; /// Barometric vertical rate valid.551bool geoVRate : 1; /// Geometric vertical rate valid.552bool baroAlt : 1; /// Barometric altitude valid.553bool surfHeading : 1; /// Surface heading valid.554bool surfSpeed : 1; /// Surface speed valid.555bool airSpeed : 1; /// Airborne speed and heading valid.556bool geoAlt : 1; /// Geometric altitude valid.557bool position : 1; /// Lat and lon data valid.558} sg_svr_validity_t;559560typedef struct561{562uint8_t reserved : 6; /// Reserved.563bool estSpeed : 1; /// Estimated N/S and E/W velocity.564bool estPosition : 1; /// Estimated lat/lon position.565} sg_svr_est_validity_t;566567/**568* The XPDR ADS-B state vector report Message.569* Host --> XPDR.570*571* @note The time of applicability values are based on the MX system clock that starts572* at 0 on power up. The time is the floating point number that is the seconds since573* power up. The time number rolls over at 512.0.574*/575typedef struct576{577sg_svr_type_t type; /// Report type.578union579{580uint8_t flags;581sg_svr_validity_t validity; /// Field validity flags.582};583union584{585uint8_t eflags;586sg_svr_est_validity_t evalidity; /// Estimated field validity flags.587};588uint32_t addr; /// Participant address.589sg_addr_type_t addrType; /// Participant address type.590float toaEst; /// Report estimated position and speed time of applicability.591float toaPosition; /// Report position time of applicability.592float toaSpeed; /// Report speed time of applicability.593uint8_t survStatus; /// Surveillance status.594uint8_t mode; /// Report mode.595uint8_t nic; /// Navigation integrity category.596float lat; /// Latitude.597float lon; /// Longitude.598union599{600sg_svr_surface_t surface; /// Surface SVR data.601sg_svr_airborne_t airborne; /// Airborne SVR data.602};603} sg_svr_t;604605typedef enum606{607msrTypeV0,608msrTypeV1Airborne,609msrTypeV1Surface,610msrTypeV2Airborne,611msrTypeV2Surface612} sg_msr_type_t;613614typedef struct615{616uint8_t reserved : 2;617bool priority : 1;618bool sil : 1;619bool nacv : 1;620bool nacp : 1;621bool opmode : 1;622bool capcodes : 1;623} sg_msr_validity_t;624625typedef enum626{627adsbVerDO260,628adsbVerDO260A,629adsbVerDO260B630} sg_adsb_version_t;631632typedef enum633{634adsbUnknown,635adsbLight,636adsbSmall = 0x3,637adsbLarge = 0x5,638adsbHighVortex,639adsbHeavy,640adsbPerformance,641adsbRotorcraft = 0x0A,642adsbGlider,643adsbAir,644adsbUnmaned,645adsbSpace,646adsbUltralight,647adsbParachutist,648adsbVehicle_emg = 0x14,649adsbVehicle_serv,650adsbObsticlePoint,651adsbObsticleCluster,652adsbObsticleLinear653} sg_adsb_emitter_t;654655typedef enum656{657priNone,658priGeneral,659priMedical,660priFuel,661priComm,662priUnlawful,663priDowned664} sg_priority_t;665666typedef enum667{668tcrNone,669tcrSingle,670tcrMultiple671} sg_tcr_t;672673typedef struct674{675bool b2low : 1;676bool uat : 1;677bool arv : 1;678bool tsr : 1;679bool adsb : 1;680bool tcas : 1;681sg_tcr_t tcr;682} sg_capability_t;683684typedef enum685{686gpsLonNodata,687gpsLonSensorSupplied,688gpsLon2m,689gpsLon4m,690gpsLon6m,691gpsLon8m,692gpsLon10m,693gpsLon12m,694gpsLon14m,695gpsLon16m,696gpsLon18m,697gpsLon20m,698gpsLon22m,699gpsLon24m,700gpsLon26m,701gpsLon28m,702gpsLon30m,703gpsLon32m,704gpsLon34m,705gpsLon36m,706gpsLon38m,707gpsLon40m,708gpsLon42m,709gpsLon44m,710gpsLon46m,711gpsLon48m,712gpsLon50m,713gpsLon52m,714gpsLon54m,715gpsLon56m,716gpsLon58m,717gpsLon60m718} sg_gps_lonofs_t;719720typedef enum721{722gpslatNodata,723gpslatLeft2m,724gpslatLeft4m,725gpslatLeft6m,726gpslatRight0m,727gpslatRight2m,728gpslatRight4m,729gpslatRight6m,730} sg_gps_latofs_t;731732typedef struct733{734bool gpsLatFmt;735sg_gps_latofs_t gpsLatOfs;736bool gpsLonFmt;737sg_gps_lonofs_t gpsLonOfs;738bool tcasRA : 1;739bool ident : 1;740bool singleAnt : 1;741} sg_adsb_opmode_t;742743typedef enum744{745gvaUnknown,746gvaLT150m,747gvaLT45m748} sg_gva_t;749750typedef enum751{752nicGolham,753nicNonGilham754} sg_nicbaro_t;755756typedef enum757{758svsilUnknown,759svsilPow3,760svsilPow5,761svsilPow7762} sg_svsil_t;763764typedef struct765{766sg_nacp_t nacp;767sg_nacv_t nacv;768sg_sda_t sda;769bool silSupp;770sg_svsil_t sil;771sg_gva_t gva;772sg_nicbaro_t nicBaro;773} sg_sv_qual_t;774775typedef enum776{777trackTrueNorth,778trackMagNorth,779headingTrueNorth,780headingMagNorth781} sg_trackheading_t;782783typedef enum784{785vrateBaroAlt,786vrateGeoAlt787} sg_vratetype_t;788789/**790* The XPDR ADS-B mode status report Message.791* Host --> XPDR.792*793* @note The time of applicability values are based on the MX system clock that starts794* at 0 on power up. The time is the floating point number that is the seconds since795* power up. The time number rolls over at 512.0.796*/797typedef struct798{799sg_msr_type_t type; /// Report type.800801union802{803uint8_t flags;804sg_msr_validity_t validity; /// Field validity flags.805};806807uint32_t addr; /// Participant address.808sg_addr_type_t addrType; /// Participant address type.809810float toa;811sg_adsb_version_t version;812char callsign[9];813sg_adsb_emitter_t emitter;814sg_size_t size;815sg_priority_t priority;816sg_capability_t capability;817sg_adsb_opmode_t opMode;818sg_sv_qual_t svQuality;819sg_trackheading_t trackHeading;820sg_vratetype_t vrateType;821} sg_msr_t;822823/**824* Convert install message struct to the raw buffer format.825*826* @param[out] buffer An empty buffer to contain the raw install message.827* @param[in] stl The install message struct with fields populated.828* @param[in] msgId The sequence number for the message.829*830* @return true if successful or false on failure.831*832* @warning data in stl parameter must be pre-validated.833*/834bool sgEncodeInstall(uint8_t *buffer, sg_install_t *stl, uint8_t msgId);835836/**837* Convert flight identification struct to the raw buffer format.838*839* @param[out] buffer An empty buffer to contain the raw flight identification message.840* @param[in] id The flight id struct with fields populated.841* @param[in] msgId The sequence number for the message.842*843* @return true if successful or false on failure.844*845* @warning data in id parameter must be pre-validated.846*/847bool sgEncodeFlightId(uint8_t *buffer, sg_flightid_t *id, uint8_t msgId);848849/**850* Convert operating message struct to the raw buffer format.851*852* @param[out] buffer An empty buffer to contain the raw operating message.853* @param[in] op The operating message struct with fields populated.854* @param[in] msgId The sequence number for the message.855*856* @return true if successful or false on failure.857*858* @warning data in op parameter must be pre-validated.859*/860bool sgEncodeOperating(uint8_t *buffer, sg_operating_t *op, uint8_t msgId);861862/* TODO: Create GPS helper functions to convert other data types --> char buffers */863864/**865* Convert GPS message struct to the raw buffer format.866*867* @param[out] buffer An empty buffer to contain the raw GPS message.868* @param[in] gps The GPS message struct with fields populated.869* @param[in] msgId The sequence number for the message.870*871* @return true if successful or false on failure.872*873* @warning data in gps parameter must be pre-validated.874*/875bool sgEncodeGPS(uint8_t *buffer, sg_gps_t *gps, uint8_t msgId);876877/**878* Convert data request message struct to the raw buffer format.879*880* @param[out] buffer An empty buffer to contain the raw target request message.881* @param[in] data The data request message struct with fields populated.882* @param[in] msgId The sequence number for the message.883*884* @return true if successful or false on failure.885*886* @warning data in data parameter must be pre-validated.887*/888bool sgEncodeDataReq(uint8_t *buffer, sg_datareq_t *data, uint8_t msgId);889890/**891* Convert target request message struct to the raw buffer format.892*893* @param[out] buffer An empty buffer to contain the raw target request message.894* @param[in] tgt The target request message struct with fields populated.895* @param[in] msgId The sequence number for the message.896*897* @return true if successful or false on failure.898*899* @warning data in tgt parameter must be pre-validated.900*/901bool sgEncodeTargetReq(uint8_t *buffer, sg_targetreq_t *tgt, uint8_t msgId);902903/**904* Process the ACK message response from the transponder.905*906* @param[in] buffer The raw ACK message buffer.907* @param[out] ack The parsed message results.908*909* @return true if successful or false on failure.910*/911bool sgDecodeAck(uint8_t *buffer, sg_ack_t *ack);912913/**914* Process the Install message response from the transponder.915*916* @param[in] buffer The raw Install message buffer.917* @param[out] stl The parsed message results.918*919* @return true if successful or false on failure.920*/921bool sgDecodeInstall(uint8_t *buffer, sg_install_t *stl);922923/**924* Process the Flight ID message response from the transponder.925*926* @param[in] buffer The raw Flight ID message buffer.927* @param[out] id The parsed message results.928*929* @return true if successful or false on failure.930*/931bool sgDecodeFlightId(uint8_t *buffer, sg_flightid_t *id);932933/**934* Process the state vector report message.935*936* @param[in] buffer The raw SVR message buffer.937* @param[out] svr The parsed SVR message.938*939* @return true if successful or false on failure.940*/941bool sgDecodeSVR(uint8_t *buffer, sg_svr_t *svr);942943/**944* Process the mode status report message.945*946* @param buffer The raw MSR message buffer.947* @param msr The parsed MSR message.948*949* @return true if successful or false on failure.950*/951bool sgDecodeMSR(uint8_t *buffer, sg_msr_t *msr);952953#endif /* SG_H */954955956