AP_ADSB: Style fixes

This commit is contained in:
nicholas-inocencio 2024-10-17 09:52:25 -05:00 committed by Randy Mackay
parent 35bc9b9b96
commit c904dab38e
4 changed files with 505 additions and 515 deletions

View File

@ -91,8 +91,7 @@ void AP_ADSB_uAvionix_UCP::update()
} // 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)
{
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)
{
request_msg(GDL90_ID_TRANSPONDER_CONFIG);
@ -115,9 +113,10 @@ void AP_ADSB_uAvionix_UCP::update()
// 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),
// 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();
}
}
if ((now_ms - run_state.last_packet_GPS_ms >= 200) && (_frontend._options & uint32_t(AP_ADSB::AdsbOption::Ping200X_Send_GPS)) != 0) {
run_state.last_packet_GPS_ms = now_ms;
@ -128,10 +127,8 @@ void AP_ADSB_uAvionix_UCP::update()
// fill the transponder status mavlink message, indicate status unavailable.
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_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;
// TODO reset the data for each message when timeout occurs
}
}
@ -230,10 +227,8 @@ void AP_ADSB_uAvionix_UCP::handle_msg(const GDL90_RX_MESSAGE &msg)
case GDL90_ID_TRANSPONDER_STATUS:
{
_frontend.out_state.tx_status.fault &= ~UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL;
switch (msg.payload[0])
{
case 1:
{
switch (msg.payload[0]) {
case 1: {
// 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));
if (rx.decoded.transponder_status.identActive) {
@ -295,8 +290,7 @@ void AP_ADSB_uAvionix_UCP::handle_msg(const GDL90_RX_MESSAGE &msg)
case 2:
// deprecated
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)
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.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 this is the first time we've seen a status message,
// and we haven't initialized the control message from the config message,

View File

@ -68,15 +68,12 @@ typedef enum
GDL90_RX_IDLE,
GDL90_RX_IN_PACKET,
GDL90_RX_UNSTUFF,
//GDL90_RX_END,
} GDL90_RX_STATE;
typedef struct
{
GDL90_RX_STATE state;
uint16_t length;
//uint32_t overflow;
//uint32_t complete;
uint8_t prev_data;
} GDL90_RX_STATUS;