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/GDL90_protocol/GDL90_Message_Structs.h
Views: 1799
/*1Copyright (C) 2021 Kraus Hamdani Aerospace Inc. All rights reserved.23This program is free software: you can redistribute it and/or modify4it under the terms of the GNU General Public License as published by5the Free Software Foundation, either version 3 of the License, or6(at your option) any later version.78This program is distributed in the hope that it will be useful,9but WITHOUT ANY WARRANTY; without even the implied warranty of10MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the11GNU General Public License for more details.1213You should have received a copy of the GNU General Public License14along with this program. If not, see <http://www.gnu.org/licenses/>.151617Author: GDL90/UCP protocol by uAvionix, 2021.18Implemented by: Tom Pittenger19*/2021#include <stddef.h>22#include <stdbool.h>23#include <stdint.h>2425typedef enum __attribute__((__packed__))26{27GDL90_ID_HEARTBEAT = 0,28GDL90_ID_OWNSHIP_REPORT = 10, // 0x0A29GDL90_ID_OWNSHIP_GEOMETRIC_ALTITUDE = 11, // 0x0B30GDL90_ID_IDENTIFICATION = 37, // 0x2531GDL90_ID_SENSOR_MESSAGE = 40, // 0x2832GDL90_ID_TRANSPONDER_CONFIG = 43, // 0x2B33GDL90_ID_MESSAGE_REQUEST = 44, // 0x2C34GDL90_ID_TRANSPONDER_CONTROL = 45, // 0x2D35GDL90_ID_GPS_DATA = 46, // 0x2E36GDL90_ID_TRANSPONDER_STATUS = 47, // 0x2F37} GDL90_MESSAGE_ID;3839typedef enum __attribute__((__packed__))40{41ADSB_NIC_BARO_UNVERIFIED = 0, // Baro is Gilman bases, and not cross checked42ADSB_NIC_BARO_VERIFIED = 1, // Baro is cross-checked, or not Gilman based43} ADSB_NIC_BARO; // Barometric Altitude Integrity Code4445typedef enum __attribute__((__packed__))46{47ADSB_AIRBORNE_SUBSONIC = 0,48ADSB_AIRBORNE_SUPERSONIC = 1,49ADSB_ON_GROUND = 2,50// 3 Reserved51} ADSB_AIR_GROUND_STATE; // Determines how horizontal velocity fields are processed in UAT5253typedef enum __attribute__((__packed__))54{55ADSB_EMERGENCY_NONE = 0,56ADSB_EMERGENCY_GENERAL = 1,57ADSB_EMERGENCY_MEDICAL = 2,58ADSB_EMERGENCY_MINIMUM_FUEL = 3,59ADSB_EMERGENCY_NO_COMMUNICATION = 4,60ADSB_EMERGNECY_INTERFERENCE = 5,61ADSB_EMERGENCY_DOWNED_AIRCRAFT = 6,62ADSB_EMERGENCY_UAS_LOST_LINK = 7,63// 7 Reserved64} ADSB_EMERGENCY_STATUS;6566#define GDL90_TRANSPONDER_CONTROL_VERSION (2)67#if GDL90_TRANSPONDER_CONTROL_VERSION == 168typedef struct __attribute__((__packed__))69{70GDL90_MESSAGE_ID messageId;71uint8_t version;72ADSB_NIC_BARO baroCrossChecked : 1;73ADSB_AIR_GROUND_STATE airGroundState : 2;74uint8_t identActive : 1;75uint8_t modeAEnabled : 1;76uint8_t modeCEnabled : 1;77uint8_t modeSEnabled : 1;78uint8_t es1090TxEnabled : 1;79int32_t externalBaroAltitude_mm;80uint16_t squawkCode;81ADSB_EMERGENCY_STATUS emergencyState;82uint8_t callsign[8];83} GDL90_TRANSPONDER_CONTROL_MSG;84#elif GDL90_TRANSPONDER_CONTROL_VERSION == 285typedef struct __attribute__((__packed__))86{87GDL90_MESSAGE_ID messageId;88uint8_t version;89ADSB_NIC_BARO baroCrossChecked : 1;90ADSB_AIR_GROUND_STATE airGroundState : 2;91uint8_t identActive : 1;92uint8_t modeAEnabled : 1;93uint8_t modeCEnabled : 1;94uint8_t modeSEnabled : 1;95uint8_t es1090TxEnabled : 1;96int32_t externalBaroAltitude_mm;97uint16_t squawkCode;98ADSB_EMERGENCY_STATUS emergencyState;99uint8_t callsign[8];100uint8_t rfu : 7;101uint8_t x_bit : 1;102} GDL90_TRANSPONDER_CONTROL_MSG;103#endif104105#define GDL90_STATUS_MAX_ALTITUDE_FT (101338)106#define GDL90_STATUS_MIN_ALTITUDE_FT (-1000)107typedef struct __attribute__((__packed__))108{109GDL90_MESSAGE_ID messageId;110uint8_t version;111uint8_t rfu : 2;112uint8_t x_bit : 1;113uint8_t identActive : 1;114uint8_t modeAEnabled : 1;115uint8_t modeCEnabled : 1;116uint8_t modeSEnabled : 1;117uint8_t es1090TxEnabled : 1;118uint16_t modeARepliesPerSecond;119uint16_t modecRepliesPerSecond;120uint16_t modeSRepliesPerSecond;121uint16_t squawkCode;122uint16_t crc;123} GDL90_TRANSPONDER_STATUS_MSG;124125typedef struct __attribute__((__packed__))126{127GDL90_MESSAGE_ID messageId;128uint8_t version;129uint8_t indicatingOnGround : 1;130uint8_t interrogatedSinceLast : 1;131uint8_t fault : 1;132uint8_t identActive : 1;133uint8_t modeAEnabled : 1;134uint8_t modeCEnabled : 1;135uint8_t modeSEnabled : 1;136uint8_t es1090TxEnabled : 1;137uint8_t latitude[3];138uint8_t longitude[3];139uint32_t track_Heading : 8;140uint32_t horizontalVelocity :12;141uint32_t altitude :12;142uint16_t squawkCode;143uint8_t NIC : 4;144uint8_t NACp : 4;145uint8_t temperature;146uint16_t crc;147} GDL90_TRANSPONDER_STATUS_MSG_V3;148149150typedef struct __attribute__((__packed__))151{152uint8_t HPLfdeActive : 1;153uint8_t fault : 1;154uint8_t HrdMagNorth : 1;155uint8_t reserved : 5;156} GDL90_GPS_NAV_STATE;157158typedef enum __attribute__((__packed__))159{160GPS_FIX_NONE = 0,161GPS_FIX_NO_FIX = 1,162GPS_FIX_2D = 2,163GPS_FIX_3D = 3,164GPS_FIX_DIFFERENTIAL = 4,165GPS_FIX_RTK = 5,166} GPS_FIX;167168typedef struct __attribute__((__packed__))169{170GDL90_MESSAGE_ID messageId;171uint8_t version;172uint32_t utcTime_s; // Time since GPS epoch173int32_t latitude_ddE7;174int32_t longitude_ddE7;175int32_t altitudeGnss_mm; // Height about WGS84 ellipsoid176// Protection Limits. FD or SBAS-based depending on state bits177uint32_t HPL_mm;178uint32_t VPL_cm;179// FOMS180uint32_t horizontalFOM_mm;181uint16_t verticalFOM_cm;182uint16_t horizontalVelocityFOM_mmps;183uint16_t verticalVelocityFOM_mmps;184// Velocities185int16_t verticalVelocity_cmps;186int32_t northVelocity_mmps; // millimeter/s187int32_t eastVelocity_mmps;188// State189GPS_FIX fixType;190GDL90_GPS_NAV_STATE navState;191uint8_t satsUsed;192} GDL90_GPS_DATA_V2;193#define GDL90_GPS_DATA_VERSION (2)194195typedef struct __attribute__((__packed__))196{197GDL90_MESSAGE_ID messageId;198uint8_t version;199GDL90_MESSAGE_ID reqMsgId;200} GDL90_TRANSPONDER_MESSAGE_REQUEST_V2;201202typedef enum __attribute__((__packed__))203{204GDL90_BARO_DATA_SOURCE_INTERNAL = 0,205GDL90_BARO_DATA_SOURCE_EXTERNAL,206}GDL90_BARO_DATA_SOURCE;207208typedef enum __attribute__((__packed__))209{210ADSB_SDA_UNKNOWN = 0,211ADSB_SDA_10_NEG3 = 1,212ADSB_SDA_10_NEG5 = 2,213ADSB_SDA_10_NEG7 = 3,214} ADSB_SDA; // System Design Assurance215216typedef enum __attribute__((__packed__))217{218ADSB_SIL_UNKNOWN = 0,219ADSB_SIL_10_NEG3 = 1,220ADSB_SIL_10_NEG5 = 2,221ADSB_SIL_10_NEG7 = 3,222} ADSB_SIL; // Source Integrity Level223224typedef enum __attribute__((__packed__))225{226ADSB_AV_LW_NO_DATA = 0,227ADSB_AV_LW_15M_23M = 1,228ADSB_AV_LW_25M_28P5M = 2,229ADSB_AV_LW_25M_34M = 3,230ADSB_AV_LW_35M_33M = 4,231ADSB_AV_LW_35M_38M = 5,232ADSB_AV_LW_45M_39P5M = 6,233ADSB_AV_LW_45M_45M = 7,234ADSB_AV_LW_55M_45M = 8,235ADSB_AV_LW_55M_52M = 9,236ADSB_AV_LW_65M_59P5M = 10,237ADSB_AV_LW_65M_67M = 11,238ADSB_AV_LW_75M_72P5M = 12,239ADSB_AV_LW_75M_80M = 13,240ADSB_AV_LW_85M_80M = 14,241ADSB_AV_LW_85M_90M = 15,242} ADSB_AIRCRAFT_LENGTH_WIDTH;243244typedef enum __attribute__((__packed__))245{246ADSB_NOT_UAT_IN_CAPABLE = 0,247ADSB_UAT_IN_CAPABLE = 1248} ADSB_UAT_IN_CAPABILITY;249250typedef enum __attribute__((__packed__))251{252ADSB_NOT_1090ES_IN_CAPABLE = 0,253ADSB_1090ES_IN_CAPABLE = 1254} ADSB_1090ES_IN_CAPABILITY;255256typedef enum __attribute__((__packed__))257{258ADSB_GPS_LON_NO_DATA = 0,259ADSB_GPS_LON_FROM_SENSOR = 1,260// 2 - 31 valid values in 2 meter increments261} ADSB_GPS_LONGITUDINAL_OFFSET;262263typedef enum __attribute__((__packed__))264{265ADSB_GPS_LAT_NO_DATA = 0,266ADSB_GPS_LAT_LEFT_2M = 1,267ADSB_GPS_LAT_LEFT_4M = 2,268ADSB_GPS_LAT_LEFT_6M = 3,269ADSB_GPS_LAT_0M = 4,270ADSB_GPS_LAT_RIGHT_2M = 5,271ADSB_GPS_LAT_RIGHT_4M = 6,272ADSB_GPS_LAT_RIGHT_6M = 7,273} ADSB_GPS_LATERAL_OFFSET;274275typedef enum __attribute__((__packed__))276{277ADSB_EMITTER_NO_INFO = 0,278ADSB_EMITTER_LIGHT = 1,279ADSB_EMITTER_SMALL = 2,280ADSB_EMITTER_LARGE = 3,281ADSB_EMITTER_HIGH_VORTEX_LARGE = 4,282ADSB_EMITTER_HEAVY = 5,283ADSB_EMITTER_HIGHLY_MANUV = 6,284ADSB_EMITTER_ROTOCRAFT = 7,285// 8 Unassigned286ADSB_EMITTER_GLIDER = 9,287ADSB_EMITTER_LIGHTER_AIR = 10,288ADSB_EMITTER_PARACHUTE = 11,289ADSB_EMITTER_ULTRA_LIGHT = 12,290// 13 Unassigned291ADSB_EMITTER_UAV = 14,292ADSB_EMITTER_SPACE = 15,293// 16 Unassigned294295// Surface types296ADSB_EMITTER_EMERGENCY_SURFACE = 17,297ADSB_EMITTER_SERVICE_SURFACE = 18,298299// Obstacle types300ADSB_EMITTER_POINT_OBSTACLE = 19,301ADSB_EMITTER_CLUSTER_OBSTACLE = 20,302ADSB_EMITTER_LINE_OBSTACLE = 21,303// 22 - 39 Reserved304} ADSB_EMITTER; // ADSB Emitter Category305306typedef enum __attribute__((__packed__))307{308PING_COM_1200_BAUD = 0,309PING_COM_2400_BAUD = 1,310PING_COM_4800_BAUD = 2,311PING_COM_9600_BAUD = 3,312PING_COM_19200_BAUD = 4,313PING_COM_38400_BAUD = 5,314PING_COM_57600_BAUD = 6,315PING_COM_115200_BAUD = 7,316PING_COM_921600_BAUD = 8,317} PING_COM_RATE;318319typedef enum __attribute__((__packed__))320{321CONFIG_VALIDITY_ICAO = 1 << 0,322CONFIG_VALIDITY_SIL = 1 << 1,323CONFIG_VALIDITY_SDA = 1 << 2,324CONFIG_VALIDITY_BARO_ALT_SOURCE = 1 << 3,325CONFIG_VALIDITY_AIRCRAFT_MAX_SPEED = 1 << 4,326CONFIG_VALIDITY_TEST_MODE = 1 << 5,327CONFIG_VALIDITY_ADSB_IN_CAP = 1 << 6,328CONFIG_VALIDITY_AIRCRAFT_LEN_WIDTH = 1 << 7,329CONFIG_VALIDITY_ANT_LAT_OFFSET = 1 << 8,330CONFIG_VALIDITY_ANT_LONG_OFFSET = 1 << 9,331CONFIG_VALIDITY_AIRCRAFT_REG = 1 << 10,332CONFIG_VALIDITY_AIRCRAFT_STALL_SPEED = 1 << 11,333CONFIG_VALIDITY_AIRCRAFT_EMITTER_TYPE = 1 << 12,334CONFIG_VALIDITY_DEF_1090ES_TX_MODE = 1 << 13,335CONFIG_VALIDITY_DEF_MODES_REPLY_MODE = 1 << 14,336CONFIG_VALIDITY_DEF_MODEC_REPLY_MODE = 1 << 15,337CONFIG_VALIDITY_DEF_MODEA_REPLY_MODE = 1 << 16,338CONFIG_VALIDITY_SERIAL_BAUD_RATE = 1 << 17,339CONFIG_VALIDITY_DEF_MODEA_SQUAWK = 1 << 18,340CONFIG_VALIDITY_BARO_100 = 1 << 19,341CONFIG_VALIDITY_IN_PROTOCOL = 1 << 20,342CONFIG_VALIDITY_OUT_PROTOCOL = 1 << 21,343} CONFIG_VALIDITY;344345typedef union __attribute__((__packed__))346{347struct __attribute__((__packed__))348{349uint32_t icaoValid : 1;350uint32_t silValid : 1;351uint32_t sdaValid : 1;352uint32_t baroAltSourceValid : 1;353uint32_t aircraftMaxSpeedValid : 1;354uint32_t testModeValid : 1;355uint32_t adsbInCapValid : 1;356uint32_t aircraftLenWidthValid : 1;357uint32_t aircraftLatOffsetValid : 1;358uint32_t aircraftLongOffsetValid : 1;359uint32_t aircraftRegValid : 1;360uint32_t aircraftStallSpeedValid : 1;361uint32_t aircraftEmitterCatValid : 1;362uint32_t default1090ExTxModeValid : 1;363uint32_t defaultModeSReplyModeValid : 1;364uint32_t defaultModeCReplyModeValid : 1;365uint32_t defaultModeAReplyModeValid : 1;366uint32_t serialBaudRateValid : 1;367uint32_t defaultModeASquawkValid : 1;368uint32_t baro100Valid : 1;369uint32_t inProtocolValid : 1;370uint32_t outProtocolValid : 1;371uint32_t reserved : 10;372};373CONFIG_VALIDITY raw;374} CONFIG_VALIDITY_BITMASK;375376typedef enum __attribute__((__packed__))377{378PING_PROTOCOL_NONE = 0,379PING_PROTOCOL_MAVLINK = 1 << 0,380PING_PROTOCOL_UCP = 1 << 1,381PING_PROTOCOL_APOLLO = 1 << 9,382PING_PROTOCOL_UCP_HD = 1 << 10,383} PING_PROTOCOL;384385typedef union386{387struct __attribute__((__packed__))388{389uint16_t mavlink : 1;390uint16_t ucp : 1;391uint16_t reserved1 : 7;392uint16_t apollo : 1;393uint16_t ucphd : 1;394uint16_t reserved2 : 5;395};396PING_PROTOCOL raw;397} PING_PROTOCOL_MASK;398399typedef struct __attribute__((__packed__))400{401GDL90_MESSAGE_ID messageId;402uint8_t version;403uint8_t icaoAddress[3];404uint8_t maxSpeed : 3;405GDL90_BARO_DATA_SOURCE baroAltSource : 1;406ADSB_SDA SDA : 2;407ADSB_SIL SIL : 2;408ADSB_AIRCRAFT_LENGTH_WIDTH lengthWidth : 4;409ADSB_1090ES_IN_CAPABILITY es1090InCapable : 1;410ADSB_UAT_IN_CAPABILITY uatInCapable : 1;411uint8_t testMode : 2;412ADSB_GPS_LONGITUDINAL_OFFSET longitudinalOffset : 5;413ADSB_GPS_LATERAL_OFFSET lateralOffset : 3;414uint8_t registration[8];415uint16_t stallSpeed_cmps;416ADSB_EMITTER emitterType;417PING_COM_RATE baudRate : 4;418uint8_t modeAEnabled : 1;419uint8_t modeCEnabled : 1;420uint8_t modeSEnabled : 1;421uint8_t es1090TxEnabled : 1;422uint16_t defaultSquawk;423CONFIG_VALIDITY_BITMASK valdityBitmask;424uint8_t rfu : 7;425uint8_t baro100 : 1;426PING_PROTOCOL_MASK inProtocol;427PING_PROTOCOL_MASK outProtocol;428uint16_t crc;429} GDL90_TRANSPONDER_CONFIG_MSG_V4_V5;430431432typedef struct __attribute__((__packed__))433{434uint8_t fwMajorVersion;435uint8_t fwMinorVersion;436uint8_t fwBuildVersion;437uint8_t hwId; // TODO Ugh should be 16 bits438uint64_t serialNumber;439} GDL90_DEVICE_ID;440441typedef struct __attribute__((__packed__))442{443GDL90_MESSAGE_ID messageId;444uint8_t protocolVersion;445GDL90_DEVICE_ID primary;446GDL90_DEVICE_ID secondary;447uint8_t primaryFWID;448uint32_t primaryCRC;449uint8_t secondaryFWID;450uint32_t secondaryCRC;451uint8_t primaryFwPartNumber[15];452uint8_t secondaryFwPartNumber[15];453uint16_t crc;454} GDL90_IDENTIFICATION_V3;455#define GDL90_IDENT_PROTOCOL_VERSION (3)456457458typedef struct __attribute__((__packed__))459{460struct461{462uint8_t uatInitialized : 1;463464// GDL90 public spec defines next bit as reserved465// uAvionix maps extra failure condition466uint8_t functionFailureGnssDataFrequency : 1;467468uint8_t ratcs : 1;469uint8_t gpsBatteryLow : 1;470uint8_t addressType : 1;471uint8_t ident : 1;472uint8_t maintenanceRequired : 1;473uint8_t gpsPositionValid : 1;474} one;475struct __attribute__((__packed__))476{477478uint8_t utcOk : 1;479480// GDL90 public spec defines next four bits as reserved481// uAvionix maps extra failure conditions482uint8_t functionFailureGnssUnavailable : 1;483uint8_t functionFailureGnssNo3dFix : 1;484uint8_t functionFailureBroadcastMonitor : 1;485uint8_t functionFailureTransmitSystem : 1;486487uint8_t csaNotAvailable : 1;488uint8_t csaRequested : 1;489uint8_t timestampMsb : 1;490} two;491} GDL90_HEARTBEAT_STATUS;492493typedef struct __attribute__((__packed__))494{495GDL90_MESSAGE_ID messageId;496GDL90_HEARTBEAT_STATUS status;497uint16_t timestamp;498499// Need to flip before TX500union501{502struct __attribute__((__packed__))503{504uint16_t uatMessages : 10;505uint16_t rfu : 1;506uint16_t uplinkMessages : 5;507};508uint16_t messageCount;509};510uint16_t crc;511} GDL90_HEARTBEAT;512513typedef enum __attribute__((__packed__))514{515GDL90_ADDRESS_ADSB_ICAO,516GDL90_ADDRESS_ADSB_SELF_ASSIGNED,517GDL90_ADDRESS_TISB_ICAO,518GDL90_ADDRESS_TISB_TRACK_ID,519GDL90_ADDRESS_SURFACE,520GDL90_ADDRESS_GROUND_BEACON,521} GDL90_ADDRESS_TYPE;522523typedef enum __attribute__((__packed__))524{525GDL90_NO_ALERT,526GDL90_ALERT,527} GDL90_TRAFFIC_ALERT;528529typedef enum __attribute__((__packed__))530{531GDL90_MISC_INVALID,532GDL90_MISC_TRUE_TRACK,533GDL90_MISC_HEADING_MAGNETIC,534GDL90_MISC_HEADING_TRUE,535} GDL90_MISC_TRACK_TYPE;536537typedef enum __attribute__((__packed__))538{539GDL90_MISC_REPORT_UPDATED,540GDL90_MISC_REPORT_EXTRAPOLATED,541} GDL90_MISC_REPORT_TYPE;542543typedef enum __attribute__((__packed__))544{545GDL90_MISC_ON_GROUND,546GDL90_MISC_AIRBORNE,547} GDL90_MISC_AG_STATE;548549typedef union550{551struct __attribute__((__packed__))552{553GDL90_MISC_TRACK_TYPE track : 2;554GDL90_MISC_REPORT_TYPE reportType : 1;555GDL90_MISC_AG_STATE agState : 1;556};557uint8_t data;558} GDL90_MISCELLANEOUS;559560typedef struct __attribute__((__packed__))561{562GDL90_ADDRESS_TYPE addressType: 4;563GDL90_TRAFFIC_ALERT trafficAlert : 4;564565uint8_t address[3];566567uint8_t latitude[3]; // 180 deg / 2^23568uint8_t longitude[3]; // 180 deg / 2^23569570// Byte order must be flipped before TX571union572{573struct __attribute__((__packed__))574{575uint16_t misc : 4;576uint16_t altitude : 12;577};578uint16_t altitudeMisc;579};580581uint8_t NACp : 4;582uint8_t NIC : 4;583584// Byte order must be flipped before TX585union586{587struct __attribute__((__packed__))588{589uint32_t heading : 8;590uint32_t verticalVelocity : 12;591uint32_t horizontalVelocity : 12;592};593uint32_t velocities;594};595596uint8_t emitterCategory;597uint8_t callsign[8];598599uint8_t rfu : 4;600uint8_t emergencyCode : 4;601} GDL90_REPORT;602603typedef struct __attribute__((__packed__))604{605GDL90_MESSAGE_ID messageId;606GDL90_REPORT report;607uint16_t crc;608} GDL90_OWNSHIP_REPORT;609typedef GDL90_OWNSHIP_REPORT GDL90_TRAFFIC_REPORT;610611typedef enum __attribute__((__packed__))612{613GDL90_NO_WARNING,614GDL90_WARNING,615} GDL90_VERTICAL_WARNING;616617typedef struct __attribute__((__packed__))618{619GDL90_MESSAGE_ID messageId;620uint16_t geometricAltitude; // 5 ft resolution621622// Must be endian swapped before TX623union624{625struct __attribute__((__packed__))626{627uint16_t verticalFOM : 15;628GDL90_VERTICAL_WARNING verticalWarning : 1;629};630uint16_t veritcalMetrics;631};632uint16_t crc;633} GDL90_OWNSHIP_GEO_ALTITUDE;634635typedef enum __attribute__((__packed__))636{637GDL90_SENSOR_AHRS = 0,638GDL90_SENSOR_BARO = 1,639GDL90_SENSOR_CO = 2,640GDL90_SENSOR_DEVICE = 3641} GDL90_SENSOR_TYPE;642643typedef struct __attribute__((__packed__))644{645GDL90_MESSAGE_ID messageId;646GDL90_SENSOR_TYPE sensorType;647uint32_t pressure_mbarE2;648int32_t pressureAlt_mm;649int16_t temperature_cE2;650uint16_t crc;651} GDL90_SENSOR_BARO_MESSAGE;652653654655