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/sgDecodeInstall.c
Views: 1799
/**1* @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved.2*3* @file sgDecodeInstall.c4* @author Jacob.Garrison5*6* @date Mar 9, 20217*8*/910#include <string.h>11#include <stdbool.h>1213#include "sg.h"14#include "sgUtil.h"1516#define SG_REG_LEN 7 // The number of bytes in the registration field1718#define SG_STL_ANTENNA 0x0319#define SG_STL_ALT_RES 0x0820#define SG_STL_HDG_TYPE 0x1021#define SG_STL_SPD_TYPE 0x2022#define SG_STL_HEATER 0x4023#define SG_STL_WOW 0x802425typedef struct __attribute__((packed))26{27uint8_t start;28uint8_t type;29uint8_t id;30uint8_t payloadLen;31uint8_t icao[3];32char registration[SG_REG_LEN];33uint8_t rsvd1[2];34uint8_t com0;35uint8_t com1;36uint8_t ipAddress[4];37uint8_t subnetMask[4];38uint8_t port[2];39uint8_t gpsIntegrity;40uint8_t emitterSet;41uint8_t emitterType;42uint8_t size;43uint8_t maxSpeed;44uint8_t altOffset[2];45uint8_t rsvd2[2];46uint8_t config;47uint8_t rsvd3[2];48uint8_t checksum;49} stl_t;5051/*52* Documented in the header file.53*/54bool sgDecodeInstall(uint8_t *buffer, sg_install_t *stl)55{56memset(&stl->reg[0], '\0', sizeof(stl->reg)); // Ensure registration is null-terminated5758stl_t sgStl;59memcpy(&sgStl, buffer, sizeof(stl_t));6061stl->icao = toIcao(sgStl.icao);62strcpy(stl->reg, sgStl.registration);63memset(&stl->reg[SG_REG_LEN], 0, 1); // Ensure registration is null-terminated64stl->com0 = (sg_baud_t)(sgStl.com0);65stl->com1 = (sg_baud_t)(sgStl.com1);66stl->eth.ipAddress = toUint32(sgStl.ipAddress);67stl->eth.subnetMask = toUint32(sgStl.subnetMask);68stl->eth.portNumber = toUint16(sgStl.port);69stl->sil = (sg_sil_t)(sgStl.gpsIntegrity >> 4);70stl->sda = (sg_sda_t)(sgStl.gpsIntegrity & 0x0F);71stl->emitter = (sg_emitter_t)(0x10 * sgStl.emitterSet + sgStl.emitterType);72stl->size = (sg_size_t)sgStl.size;73stl->maxSpeed = (sg_airspeed_t)sgStl.maxSpeed;74stl->altOffset = toUint16(sgStl.altOffset);75stl->antenna = (sg_antenna_t)sgStl.config & SG_STL_ANTENNA;76stl->altRes100 = sgStl.config & SG_STL_ALT_RES;77stl->hdgTrueNorth = sgStl.config & SG_STL_HDG_TYPE;78stl->airspeedTrue = sgStl.config & SG_STL_SPD_TYPE;79stl->heater = sgStl.config & SG_STL_HEATER;80stl->wowConnected = sgStl.config & SG_STL_WOW;8182return true;83}848586