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/sgDecodeInstall.c
Views: 1799
1
/**
2
* @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved.
3
*
4
* @file sgDecodeInstall.c
5
* @author Jacob.Garrison
6
*
7
* @date Mar 9, 2021
8
*
9
*/
10
11
#include <string.h>
12
#include <stdbool.h>
13
14
#include "sg.h"
15
#include "sgUtil.h"
16
17
#define SG_REG_LEN 7 // The number of bytes in the registration field
18
19
#define SG_STL_ANTENNA 0x03
20
#define SG_STL_ALT_RES 0x08
21
#define SG_STL_HDG_TYPE 0x10
22
#define SG_STL_SPD_TYPE 0x20
23
#define SG_STL_HEATER 0x40
24
#define SG_STL_WOW 0x80
25
26
typedef struct __attribute__((packed))
27
{
28
uint8_t start;
29
uint8_t type;
30
uint8_t id;
31
uint8_t payloadLen;
32
uint8_t icao[3];
33
char registration[SG_REG_LEN];
34
uint8_t rsvd1[2];
35
uint8_t com0;
36
uint8_t com1;
37
uint8_t ipAddress[4];
38
uint8_t subnetMask[4];
39
uint8_t port[2];
40
uint8_t gpsIntegrity;
41
uint8_t emitterSet;
42
uint8_t emitterType;
43
uint8_t size;
44
uint8_t maxSpeed;
45
uint8_t altOffset[2];
46
uint8_t rsvd2[2];
47
uint8_t config;
48
uint8_t rsvd3[2];
49
uint8_t checksum;
50
} stl_t;
51
52
/*
53
* Documented in the header file.
54
*/
55
bool sgDecodeInstall(uint8_t *buffer, sg_install_t *stl)
56
{
57
memset(&stl->reg[0], '\0', sizeof(stl->reg)); // Ensure registration is null-terminated
58
59
stl_t sgStl;
60
memcpy(&sgStl, buffer, sizeof(stl_t));
61
62
stl->icao = toIcao(sgStl.icao);
63
strcpy(stl->reg, sgStl.registration);
64
memset(&stl->reg[SG_REG_LEN], 0, 1); // Ensure registration is null-terminated
65
stl->com0 = (sg_baud_t)(sgStl.com0);
66
stl->com1 = (sg_baud_t)(sgStl.com1);
67
stl->eth.ipAddress = toUint32(sgStl.ipAddress);
68
stl->eth.subnetMask = toUint32(sgStl.subnetMask);
69
stl->eth.portNumber = toUint16(sgStl.port);
70
stl->sil = (sg_sil_t)(sgStl.gpsIntegrity >> 4);
71
stl->sda = (sg_sda_t)(sgStl.gpsIntegrity & 0x0F);
72
stl->emitter = (sg_emitter_t)(0x10 * sgStl.emitterSet + sgStl.emitterType);
73
stl->size = (sg_size_t)sgStl.size;
74
stl->maxSpeed = (sg_airspeed_t)sgStl.maxSpeed;
75
stl->altOffset = toUint16(sgStl.altOffset);
76
stl->antenna = (sg_antenna_t)sgStl.config & SG_STL_ANTENNA;
77
stl->altRes100 = sgStl.config & SG_STL_ALT_RES;
78
stl->hdgTrueNorth = sgStl.config & SG_STL_HDG_TYPE;
79
stl->airspeedTrue = sgStl.config & SG_STL_SPD_TYPE;
80
stl->heater = sgStl.config & SG_STL_HEATER;
81
stl->wowConnected = sgStl.config & SG_STL_WOW;
82
83
return true;
84
}
85
86