AP_ADSB: Style fixes

This commit is contained in:
nicholas-inocencio 2024-10-17 09:52:25 -05:00 committed by Tom Pittenger
parent 7a6031c746
commit c270c392c4
4 changed files with 505 additions and 515 deletions

View File

@ -90,9 +90,8 @@ void AP_ADSB_uAvionix_UCP::update()
} }
} // while nbytes } // while nbytes
if (run_state.last_packet_Transponder_Id_ms == 0 && run_state.request_Transponder_Id_tries < 5) if (run_state.last_packet_Transponder_Id_ms == 0 && run_state.request_Transponder_Id_tries < 5) {
{
if (now_ms - run_state.last_packet_Request_Transponder_Id_ms >= 1000) if (now_ms - run_state.last_packet_Request_Transponder_Id_ms >= 1000)
{ {
request_msg(GDL90_ID_IDENTIFICATION); request_msg(GDL90_ID_IDENTIFICATION);
@ -100,8 +99,7 @@ void AP_ADSB_uAvionix_UCP::update()
} }
} }
if (run_state.last_packet_Transponder_Config_ms == 0 && run_state.request_Transponder_Config_tries < 5) if (run_state.last_packet_Transponder_Config_ms == 0 && run_state.request_Transponder_Config_tries < 5) {
{
if (now_ms - run_state.last_packet_Request_Transponder_Config_ms >= 1000) if (now_ms - run_state.last_packet_Request_Transponder_Config_ms >= 1000)
{ {
request_msg(GDL90_ID_TRANSPONDER_CONFIG); request_msg(GDL90_ID_TRANSPONDER_CONFIG);
@ -114,9 +112,10 @@ void AP_ADSB_uAvionix_UCP::update()
// We want to use the defaults stored on the ping200X, if possible. // We want to use the defaults stored on the ping200X, if possible.
// Until we get the config message (or we've tried requesting it several times), // Until we get the config message (or we've tried requesting it several times),
// don't send the control message. // don't send the control message.
if (run_state.last_packet_Transponder_Config_ms != 0 || run_state.request_Transponder_Config_tries >= 5) if (run_state.last_packet_Transponder_Config_ms != 0 || run_state.request_Transponder_Config_tries >= 5) {
send_Transponder_Control(); send_Transponder_Control();
}
} }
if ((now_ms - run_state.last_packet_GPS_ms >= 200) && (_frontend._options & uint32_t(AP_ADSB::AdsbOption::Ping200X_Send_GPS)) != 0) { if ((now_ms - run_state.last_packet_GPS_ms >= 200) && (_frontend._options & uint32_t(AP_ADSB::AdsbOption::Ping200X_Send_GPS)) != 0) {
@ -124,14 +123,12 @@ void AP_ADSB_uAvionix_UCP::update()
send_GPS_Data(); send_GPS_Data();
} }
// if the transponder has stopped giving us the data needed to // if the transponder has stopped giving us the data needed to
// fill the transponder status mavlink message, indicate status unavailable. // fill the transponder status mavlink message, indicate status unavailable.
if ((now_ms - run_state.last_packet_Transponder_Status_ms >= 10000) if ((now_ms - run_state.last_packet_Transponder_Status_ms >= 10000)
&& (now_ms - run_state.last_packet_Transponder_Heartbeat_ms >= 10000) && (now_ms - run_state.last_packet_Transponder_Heartbeat_ms >= 10000)
&& (now_ms - run_state.last_packet_Transponder_Ownship_ms >= 10000)) && (now_ms - run_state.last_packet_Transponder_Ownship_ms >= 10000)) {
{
_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;
// TODO reset the data for each message when timeout occurs
} }
} }
@ -187,7 +184,7 @@ void AP_ADSB_uAvionix_UCP::handle_msg(const GDL90_RX_MESSAGE &msg)
char primaryFwPartNumber[str_len+1]; char primaryFwPartNumber[str_len+1];
memcpy(&primaryFwPartNumber, rx.decoded.identification.primaryFwPartNumber, str_len); memcpy(&primaryFwPartNumber, rx.decoded.identification.primaryFwPartNumber, str_len);
primaryFwPartNumber[str_len] = 0; primaryFwPartNumber[str_len] = 0;
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG,"ADSB:Detected %s v%u.%u.%u SN:%u %s", GCS_SEND_TEXT(MAV_SEVERITY_DEBUG,"ADSB:Detected %s v%u.%u.%u SN:%u %s",
get_hardware_name(rx.decoded.identification.primary.hwId), get_hardware_name(rx.decoded.identification.primary.hwId),
(unsigned)rx.decoded.identification.primary.fwMajorVersion, (unsigned)rx.decoded.identification.primary.fwMajorVersion,
@ -230,10 +227,8 @@ void AP_ADSB_uAvionix_UCP::handle_msg(const GDL90_RX_MESSAGE &msg)
case GDL90_ID_TRANSPONDER_STATUS: case GDL90_ID_TRANSPONDER_STATUS:
{ {
_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;
switch (msg.payload[0]) switch (msg.payload[0]) {
{ case 1: {
case 1:
{
// version 1 of the transponder status message is sent at 1 Hz (if UCP protocol out is enabled on the transponder) // version 1 of the transponder status message is sent at 1 Hz (if UCP protocol out is enabled on the transponder)
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) {
@ -295,8 +290,7 @@ void AP_ADSB_uAvionix_UCP::handle_msg(const GDL90_RX_MESSAGE &msg)
case 2: case 2:
// deprecated // deprecated
break; break;
case 3: case 3: {
{
// Version 3 of the transponder status message is sent in response to the transponder control message (if UCP-HD protocol out is enabled on the transponder) // Version 3 of the transponder status message is sent in response to the transponder control message (if UCP-HD protocol out is enabled on the transponder)
memcpy(&rx.decoded.transponder_status_v3, msg.raw, sizeof(rx.decoded.transponder_status_v3)); memcpy(&rx.decoded.transponder_status_v3, msg.raw, sizeof(rx.decoded.transponder_status_v3));
@ -345,7 +339,6 @@ void AP_ADSB_uAvionix_UCP::handle_msg(const GDL90_RX_MESSAGE &msg)
_frontend.out_state.tx_status.NIC_NACp = rx.decoded.transponder_status_v3.NIC | (rx.decoded.transponder_status_v3.NACp << 4); _frontend.out_state.tx_status.NIC_NACp = rx.decoded.transponder_status_v3.NIC | (rx.decoded.transponder_status_v3.NACp << 4);
_frontend.out_state.tx_status.boardTemp = rx.decoded.transponder_status_v3.temperature; _frontend.out_state.tx_status.boardTemp = rx.decoded.transponder_status_v3.temperature;
// TODO not the best approach
if (run_state.last_packet_Transponder_Status_ms == 0 && run_state.last_packet_Transponder_Config_ms == 0) { if (run_state.last_packet_Transponder_Status_ms == 0 && run_state.last_packet_Transponder_Config_ms == 0) {
// If this is the first time we've seen a status message, // If this is the first time we've seen a status message,
// and we haven't initialized the control message from the config message, // and we haven't initialized the control message from the config message,
@ -535,14 +528,14 @@ uint16_t AP_ADSB_uAvionix_UCP::gdl90Transmit(GDL90_TX_MESSAGE &message, const ui
// Set flag byte in frame buffer // Set flag byte in frame buffer
gdl90FrameBuffer[0] = GDL90_FLAG_BYTE; gdl90FrameBuffer[0] = GDL90_FLAG_BYTE;
uint16_t frameIndex = 1; uint16_t frameIndex = 1;
// Copy and stuff all payload bytes into frame buffer // Copy and stuff all payload bytes into frame buffer
for (uint16_t i = 0; i < length+2; i++) { for (uint16_t i = 0; i < length+2; i++) {
// Check for overflow of frame buffer // Check for overflow of frame buffer
if (frameIndex >= GDL90_TX_MAX_FRAME_LENGTH) { if (frameIndex >= GDL90_TX_MAX_FRAME_LENGTH) {
return 0; return 0;
} }
uint8_t data; uint8_t data;
// Append CRC to payload // Append CRC to payload
if (i == length) { if (i == length) {
@ -550,7 +543,7 @@ uint16_t AP_ADSB_uAvionix_UCP::gdl90Transmit(GDL90_TX_MESSAGE &message, const ui
} else if (i == length+1) { } else if (i == length+1) {
data = HIGHBYTE(frameCrc); data = HIGHBYTE(frameCrc);
} else { } else {
data = message.raw[i]; data = message.raw[i];
} }
if (data == GDL90_FLAG_BYTE || data == GDL90_CONTROL_ESCAPE_BYTE) { if (data == GDL90_FLAG_BYTE || data == GDL90_CONTROL_ESCAPE_BYTE) {
@ -558,7 +551,7 @@ uint16_t AP_ADSB_uAvionix_UCP::gdl90Transmit(GDL90_TX_MESSAGE &message, const ui
if (frameIndex + 2 > GDL90_TX_MAX_FRAME_LENGTH) { if (frameIndex + 2 > GDL90_TX_MAX_FRAME_LENGTH) {
return 0; return 0;
} }
// Set control break and stuff this byte // Set control break and stuff this byte
gdl90FrameBuffer[frameIndex++] = GDL90_CONTROL_ESCAPE_BYTE; gdl90FrameBuffer[frameIndex++] = GDL90_CONTROL_ESCAPE_BYTE;
gdl90FrameBuffer[frameIndex++] = data ^ GDL90_STUFF_BYTE; gdl90FrameBuffer[frameIndex++] = data ^ GDL90_STUFF_BYTE;
@ -566,7 +559,7 @@ uint16_t AP_ADSB_uAvionix_UCP::gdl90Transmit(GDL90_TX_MESSAGE &message, const ui
gdl90FrameBuffer[frameIndex++] = data; gdl90FrameBuffer[frameIndex++] = data;
} }
} }
// Add end of frame indication // Add end of frame indication
gdl90FrameBuffer[frameIndex++] = GDL90_FLAG_BYTE; gdl90FrameBuffer[frameIndex++] = GDL90_FLAG_BYTE;
@ -574,7 +567,7 @@ uint16_t AP_ADSB_uAvionix_UCP::gdl90Transmit(GDL90_TX_MESSAGE &message, const ui
if (hostTransmit(gdl90FrameBuffer, frameIndex)) { if (hostTransmit(gdl90FrameBuffer, frameIndex)) {
return frameIndex; return frameIndex;
} }
return 0; return 0;
} }

View File

@ -82,7 +82,7 @@ private:
uint32_t last_gcs_send_message_Transponder_Status_ms; // out uint32_t last_gcs_send_message_Transponder_Status_ms; // out
uint32_t last_packet_Request_Transponder_Config_ms; // out uint32_t last_packet_Request_Transponder_Config_ms; // out
uint32_t last_packet_Transponder_Config_ms; // in uint32_t last_packet_Transponder_Config_ms; // in
uint32_t request_Transponder_Config_tries; uint32_t request_Transponder_Config_tries;
uint32_t last_packet_Request_Transponder_Id_ms; // out uint32_t last_packet_Request_Transponder_Id_ms; // out
uint32_t last_packet_Transponder_Id_ms; // in uint32_t last_packet_Transponder_Id_ms; // in
uint32_t request_Transponder_Id_tries; uint32_t request_Transponder_Id_tries;

File diff suppressed because it is too large Load Diff

View File

@ -1,22 +1,22 @@
/* /*
Copyright (C) 2021 Kraus Hamdani Aerospace Inc. All rights reserved. Copyright (C) 2021 Kraus Hamdani Aerospace Inc. All rights reserved.
This program is free software: you can redistribute it and/or modify This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or the Free Software Foundation, either version 3 of the License, or
(at your option) any later version. (at your option) any later version.
This program is distributed in the hope that it will be useful, This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details. GNU General Public License for more details.
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>. along with this program. If not, see <http://www.gnu.org/licenses/>.
Author: GDL90/UCP protocol by uAvionix, 2021. Author: GDL90/UCP protocol by uAvionix, 2021.
Implemented by: Tom Pittenger Implemented by: Tom Pittenger
*/ */
#ifndef _GDL90_H_ #ifndef _GDL90_H_
@ -24,60 +24,57 @@
#include <stdint.h> #include <stdint.h>
#define GDL90_QUEUE_LENGTH (2) #define GDL90_QUEUE_LENGTH (2)
#define GDL90_FLAG_BYTE (0x7E) #define GDL90_FLAG_BYTE (0x7E)
#define GDL90_CONTROL_ESCAPE_BYTE (0x7D) #define GDL90_CONTROL_ESCAPE_BYTE (0x7D)
#define GDL90_STUFF_BYTE (0x20) #define GDL90_STUFF_BYTE (0x20)
#define GDL90_OVERHEAD_LENGTH (3) // Not counting framing bytes #define GDL90_OVERHEAD_LENGTH (3) // Not counting framing bytes
// Transmit message sizes // Transmit message sizes
#define GDL90_TX_MAX_PAYLOAD_LENGTH (552) #define GDL90_TX_MAX_PAYLOAD_LENGTH (552)
#define GDL90_TX_MAX_PACKET_LENGTH (GDL90_TX_MAX_PAYLOAD_LENGTH + GDL90_OVERHEAD_LENGTH) #define GDL90_TX_MAX_PACKET_LENGTH (GDL90_TX_MAX_PAYLOAD_LENGTH + GDL90_OVERHEAD_LENGTH)
#define GDL90_TX_MAX_FRAME_LENGTH (2 + ((15 * GDL90_TX_MAX_PACKET_LENGTH) / 10)) // IF every other byte was stuffed #define GDL90_TX_MAX_FRAME_LENGTH (2 + ((15 * GDL90_TX_MAX_PACKET_LENGTH) / 10)) // IF every other byte was stuffed
// Receive message sizes // Receive message sizes
#define GDL90_RX_MAX_PAYLOAD_LENGTH (128) #define GDL90_RX_MAX_PAYLOAD_LENGTH (128)
#define GDL90_RX_MAX_PACKET_LENGTH (GDL90_RX_MAX_PAYLOAD_LENGTH + GDL90_OVERHEAD_LENGTH) #define GDL90_RX_MAX_PACKET_LENGTH (GDL90_RX_MAX_PAYLOAD_LENGTH + GDL90_OVERHEAD_LENGTH)
typedef union __attribute__((__packed__)) typedef union __attribute__((__packed__))
{ {
struct __attribute__((__packed__)) struct __attribute__((__packed__))
{ {
GDL90_MESSAGE_ID messageId; GDL90_MESSAGE_ID messageId;
uint8_t payload[GDL90_TX_MAX_PAYLOAD_LENGTH]; uint8_t payload[GDL90_TX_MAX_PAYLOAD_LENGTH];
uint16_t crc; // Actually CRC location varies. This is a placeholder uint16_t crc; // Actually CRC location varies. This is a placeholder
}; };
uint8_t raw[GDL90_TX_MAX_PACKET_LENGTH]; uint8_t raw[GDL90_TX_MAX_PACKET_LENGTH];
} GDL90_TX_MESSAGE; } GDL90_TX_MESSAGE;
typedef union __attribute__((__packed__)) typedef union __attribute__((__packed__))
{ {
struct __attribute__((__packed__)) struct __attribute__((__packed__))
{ {
GDL90_MESSAGE_ID messageId; GDL90_MESSAGE_ID messageId;
uint8_t payload[GDL90_RX_MAX_PAYLOAD_LENGTH]; uint8_t payload[GDL90_RX_MAX_PAYLOAD_LENGTH];
uint16_t crc; // Actually CRC location varies. This is a placeholder uint16_t crc; // Actually CRC location varies. This is a placeholder
}; };
uint8_t raw[GDL90_RX_MAX_PACKET_LENGTH]; uint8_t raw[GDL90_RX_MAX_PACKET_LENGTH];
} GDL90_RX_MESSAGE; } GDL90_RX_MESSAGE;
typedef enum typedef enum
{ {
GDL90_RX_IDLE, GDL90_RX_IDLE,
GDL90_RX_IN_PACKET, GDL90_RX_IN_PACKET,
GDL90_RX_UNSTUFF, GDL90_RX_UNSTUFF,
//GDL90_RX_END,
} GDL90_RX_STATE; } GDL90_RX_STATE;
typedef struct typedef struct
{ {
GDL90_RX_STATE state; GDL90_RX_STATE state;
uint16_t length; uint16_t length;
//uint32_t overflow; uint8_t prev_data;
//uint32_t complete;
uint8_t prev_data;
} GDL90_RX_STATUS; } GDL90_RX_STATUS;
#endif #endif