AP_ADSB: UCP cleanup

This commit is contained in:
Tom Pittenger 2021-10-26 10:58:10 -07:00 committed by Tom Pittenger
parent f4ff8859e4
commit 99912e9e0f
2 changed files with 13 additions and 60 deletions

View File

@ -164,34 +164,6 @@ public:
AP_ADSB::Type get_type(uint8_t instance) const; AP_ADSB::Type get_type(uint8_t instance) const;
// struct {
// // from gdl90 status message and ownship message
// bool airborne;
// bool interrogatedSinceLast;
// bool identActive;
// bool x_bit;
// bool modeAEnabled;
// bool modeCEnabled;
// bool modeSEnabled;
// bool es1090TxEnabled;
// uint16_t squawkCode;
// uint8_t NIC;
// uint8_t NACp;
// uint8_t temperature;
// char flight_id[8];
// uint8_t fault;
// // // no connection to ping200x
// // bool noComms = 1;
// // // from gdl90 heartbeat message
// // bool functionFailureGnssNo3dFix;
// // bool functionFailureGnssUnavailable;
// // bool functionFailureTransmitSystem;
// // bool maintenanceRequired;
// } tx_status;
private: private:
static AP_ADSB *_singleton; static AP_ADSB *_singleton;

View File

@ -201,57 +201,39 @@ void AP_ADSB_uAvionix_UCP::handle_msg(const GDL90_RX_MESSAGE &msg)
case GDL90_ID_TRANSPONDER_STATUS: case GDL90_ID_TRANSPONDER_STATUS:
memcpy(&rx.decoded.transponder_status, msg.raw, sizeof(rx.decoded.transponder_status)); memcpy(&rx.decoded.transponder_status, msg.raw, sizeof(rx.decoded.transponder_status));
if (rx.decoded.transponder_status.identActive) if (rx.decoded.transponder_status.identActive) {
{
_frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE; _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE;
} } else {
else
{
_frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE; _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE;
} }
if (rx.decoded.transponder_status.modeAEnabled) if (rx.decoded.transponder_status.modeAEnabled) {
{
_frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED; _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED;
} } else {
else
{
_frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED; _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED;
} }
if (rx.decoded.transponder_status.modeCEnabled) if (rx.decoded.transponder_status.modeCEnabled) {
{
_frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED; _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED;
} } else {
else
{
_frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED; _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED;
} }
if (rx.decoded.transponder_status.modeSEnabled) if (rx.decoded.transponder_status.modeSEnabled) {
{
_frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED; _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED;
} } else {
else
{
_frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED; _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED;
} }
if (rx.decoded.transponder_status.es1090TxEnabled) if (rx.decoded.transponder_status.es1090TxEnabled) {
{
_frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED; _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED;
} } else {
else
{
_frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED; _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED;
} }
if (rx.decoded.transponder_status.x_bit) if (rx.decoded.transponder_status.x_bit) {
{
_frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED; _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED;
} } else {
else
{
_frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED; _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED;
} }
@ -259,8 +241,7 @@ void AP_ADSB_uAvionix_UCP::handle_msg(const GDL90_RX_MESSAGE &msg)
_frontend.out_state.tx_status.fault &= ~UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL; _frontend.out_state.tx_status.fault &= ~UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL;
if (run_state.last_packet_Transponder_Status_ms == 0) if (run_state.last_packet_Transponder_Status_ms == 0) {
{
// set initial control message contents to transponder defaults // set initial control message contents to transponder defaults
_frontend.out_state.ctrl.modeAEnabled = rx.decoded.transponder_status.modeAEnabled; _frontend.out_state.ctrl.modeAEnabled = rx.decoded.transponder_status.modeAEnabled;
_frontend.out_state.ctrl.modeCEnabled = rx.decoded.transponder_status.modeCEnabled; _frontend.out_state.ctrl.modeCEnabled = rx.decoded.transponder_status.modeCEnabled;