From 414a9993b3e96700118a14f6eea3bc526cb57224 Mon Sep 17 00:00:00 2001 From: Jye <14170229+JyeSmith@users.noreply.github.com> Date: Sat, 28 Dec 2024 09:09:50 +1000 Subject: [PATCH] Communicate Rx available antenna mode to the Tx (#3039) * add-tlmConfirm-to-tlm_dl-ota-packet-structure * clean up naming * Auto set True Diversity Rx into Diversity or Gemini mode based on Tx antenna mode * Auto configure Rx OTA protocol from the Tx * replace second packet memcmp with crc LR1121 working * remove unnecessary GPIO_PIN_NSS_2 check * update SX1280 driver and also remove isFirstRxIrq * update sx1276 driver and remove isFirstRxIrq * update tx_main * cleanup * update after master merge * cleanup * update LR1121 * remove comment * down link data * do not switch when in GemX mode * correct tlm_dl pkt buffer * POC fix optimising the mavlink SS payload size This reduces the number of partially filled pkts OTA via the SS. This need to be done correctly and in a generic way!!! * optimise mavlink SS packet size * correct txnb for rx diversity mode * update sx1280 and sx1276 drivers * Communite Rx available antenna mode to the Tx --- src/lib/OTA/OTA.h | 7 +++++-- src/src/rx_main.cpp | 5 ++++- src/src/tx_main.cpp | 12 ++++++++++++ 3 files changed, 21 insertions(+), 3 deletions(-) diff --git a/src/lib/OTA/OTA.h b/src/lib/OTA/OTA.h index 45425751..dba80f51 100644 --- a/src/lib/OTA/OTA.h +++ b/src/lib/OTA/OTA.h @@ -88,7 +88,8 @@ typedef struct { union { struct { OTA_LinkStats_s stats; - uint8_t free; + uint8_t trueDiversityAvailable:1, + free:7; } PACKED ul_link_stats; uint8_t payload[ELRS4_TELEMETRY_BYTES_PER_CALL]; }; @@ -144,7 +145,9 @@ typedef struct { union { struct { OTA_LinkStats_s stats; - uint8_t payload[ELRS8_TELEMETRY_BYTES_PER_CALL - sizeof(OTA_LinkStats_s)]; + uint8_t trueDiversityAvailable:1, + free:7; + uint8_t payload[ELRS8_TELEMETRY_BYTES_PER_CALL - sizeof(OTA_LinkStats_s) - 1]; } PACKED ul_link_stats; uint8_t payload[ELRS8_TELEMETRY_BYTES_PER_CALL]; // containsLinkStats == false }; diff --git a/src/src/rx_main.cpp b/src/src/rx_main.cpp index 1d8cc597..8d3f7650 100644 --- a/src/src/rx_main.cpp +++ b/src/src/rx_main.cpp @@ -471,12 +471,14 @@ bool ICACHE_RAM_ATTR HandleSendTelemetryResponse() otaPkt.std.type = PACKET_TYPE_LINKSTATS; OTA_LinkStats_s * ls; - ls = &otaPkt.full.tlm_dl.ul_link_stats.stats; // Include some advanced telemetry in the extra space // Note the use of `ul_link_stats.payload` vs just `payload` if (OtaIsFullRes) { + ls = &otaPkt.full.tlm_dl.ul_link_stats.stats; + otaPkt.full.tlm_dl.ul_link_stats.trueDiversityAvailable = isDualRadio(); + otaPkt.full.tlm_dl.tlmConfirm = MspReceiver.GetCurrentConfirm() ? 1 : 0; if (geminiMode) @@ -502,6 +504,7 @@ bool ICACHE_RAM_ATTR HandleSendTelemetryResponse() else { ls = &otaPkt.std.tlm_dl.ul_link_stats.stats; + otaPkt.std.tlm_dl.ul_link_stats.trueDiversityAvailable = isDualRadio(); LinkStatsToOta(ls); } diff --git a/src/src/tx_main.cpp b/src/src/tx_main.cpp index cc1fdd6a..46d7fc0a 100644 --- a/src/src/tx_main.cpp +++ b/src/src/tx_main.cpp @@ -205,6 +205,12 @@ bool ICACHE_RAM_ATTR ProcessTLMpacket(SX12xxDriverCommon::rx_status const status case PACKET_TYPE_LINKSTATS: LinkStatsFromOta(&ota8->tlm_dl.ul_link_stats.stats); + // The Rx only has a single radio. Force the Tx out of Gemini mode. + if (config.GetAntennaMode() == TX_RADIO_MODE_GEMINI && !ota8->tlm_dl.ul_link_stats.trueDiversityAvailable) + { + config.SetAntennaMode(TX_RADIO_MODE_SWITCH); + } + if (config.GetAntennaMode() == TX_RADIO_MODE_GEMINI) { if (Radio.GetProcessingPacketRadio() == SX12XX_Radio_1) @@ -301,6 +307,12 @@ bool ICACHE_RAM_ATTR ProcessTLMpacket(SX12xxDriverCommon::rx_status const status { case PACKET_TYPE_LINKSTATS: LinkStatsFromOta(&otaPktPtr->std.tlm_dl.ul_link_stats.stats); + + // The Rx only has a single radio. Force the Tx out of Gemini mode. + if (config.GetAntennaMode() == TX_RADIO_MODE_GEMINI && !otaPktPtr->std.tlm_dl.ul_link_stats.trueDiversityAvailable) + { + config.SetAntennaMode(TX_RADIO_MODE_SWITCH); + } break; case PACKET_TYPE_DATA: -- 2.11.4.GIT