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