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/target.c
Views: 1799
1
/**
2
* @copyright Copyright (c) 2020 SoftSolutions, Inc. All rights reserved.
3
*
4
* @File: target.c
5
* @Author: jim billmeyer
6
*
7
* @date December 11, 2020, 12:50 AM
8
*/
9
10
#include <stdlib.h>
11
#include "target.h"
12
13
static ownship_t ownship;
14
static target_t targets[XPNDR_ADSB_TARGETS] = {
15
{
16
0,
17
},
18
};
19
20
/*
21
* Documented in the header file.
22
*/
23
target_t *targetList(void)
24
{
25
return targets;
26
}
27
28
/*
29
* Documented in the header file.
30
*/
31
ownship_t *targetOwnship(void)
32
{
33
return &ownship;
34
}
35
36
/*
37
* Documented in the header file.
38
*/
39
target_t *targetFind(uint32_t icao)
40
{
41
for (uint16_t i = 0; i < XPNDR_ADSB_TARGETS; i++)
42
{
43
if (icao == targets[i].icao)
44
{
45
// clear strike counter and set find flag while preserving the used bit.
46
targets[i].flag = TARGET_FLAG_FOUND | TARGET_FLAG_USED;
47
return &targets[i];
48
}
49
}
50
51
return 0;
52
}
53
54
/*
55
* Documented in the header file.
56
*/
57
void targetPurge(void)
58
{
59
for (uint16_t i = 0; i < XPNDR_ADSB_TARGETS; i++)
60
{
61
// the the found flag was not set increment the strike counter.
62
if ((targets[i].flag & TARGET_FLAG_USED) && ((targets[i].flag & TARGET_FLAG_FOUND) == 0))
63
{
64
uint8_t strikes = (targets[i].flag & 0xFE) >> 2;
65
strikes++;
66
67
if (strikes > 5)
68
{
69
memset(&targets[i], 0, sizeof(target_t));
70
}
71
else
72
{
73
// set the strike counter and clear the found flag.
74
targets[i].flag = strikes << 2 | TARGET_FLAG_USED;
75
}
76
}
77
else
78
{
79
// clear the found flag so the target find function can set it
80
// to signal that the icao address is still in range.
81
targets[i].flag = targets[i].flag & (TARGET_FLAG_STRIKE_MASK | TARGET_FLAG_USED);
82
}
83
}
84
}
85
86
/*
87
* Documented in the header file.
88
*/
89
void targetAdd(target_t *target)
90
{
91
for (uint16_t i = 0; i < XPNDR_ADSB_TARGETS; i++)
92
{
93
if ((targets[i].flag & TARGET_FLAG_USED) == 0x0)
94
{
95
memcpy(&targets[i], target, sizeof(target_t));
96
targets[i].flag = TARGET_FLAG_USED;
97
break;
98
}
99
}
100
}
101
102
/*
103
* Documented in the header file.
104
*/
105
targetclimb_t targetClimb(int16_t vrate)
106
{
107
if (abs(vrate) < 500)
108
{
109
return trafLevel;
110
}
111
else if (vrate > 0)
112
{
113
return trafClimb;
114
}
115
else
116
{
117
return trafDescend;
118
}
119
}
120
121
/*
122
* Documented in the header file.
123
*/
124
targetalert_t targetAlert(double dist,
125
uint16_t alt,
126
int16_t nvel,
127
int16_t evel)
128
{
129
if (alt <= 3000)
130
{
131
if (dist <= 3.0)
132
{
133
return trafResolution;
134
}
135
else if (dist <= 6.0)
136
{
137
return trafAdvisory;
138
}
139
}
140
141
return trafTraffic;
142
}
143
144