From ef4257315de3fb705b5af70173a7d3aa0b2a613c Mon Sep 17 00:00:00 2001 From: StenRC-FPV <154423567+StenRC-FPV@users.noreply.github.com> Date: Fri, 22 Dec 2023 23:47:42 +0300 Subject: [PATCH] Update vtx_tramp.c for VTX Foxeer Reaper Infinity 5W & VTX iFlight BLITZ 1600mW IRC Tramp RF Power Selection Enhancement. Increasing power levels up to 5000mV for VTX Foxeer Infinity 5W & VTX iFlight BLITZ 1600mW. --- src/main/io/vtx_tramp.c | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) diff --git a/src/main/io/vtx_tramp.c b/src/main/io/vtx_tramp.c index 540c9c9f222..a6b6fcadbda 100644 --- a/src/main/io/vtx_tramp.c +++ b/src/main/io/vtx_tramp.c @@ -572,6 +572,12 @@ const char * const trampPowerNames_5G8_600[VTX_TRAMP_5G8_MAX_POWER_COUNT + 1] = const uint16_t trampPowerTable_5G8_800[VTX_TRAMP_5G8_MAX_POWER_COUNT] = { 25, 100, 200, 500, 800 }; const char * const trampPowerNames_5G8_800[VTX_TRAMP_5G8_MAX_POWER_COUNT + 1] = { "---", "25 ", "100", "200", "500", "800" }; +const uint16_t trampPowerTable_5G8_1600[VTX_TRAMP_5G8_MAX_POWER_COUNT] = { 25, 400, 800, 1600, 1600 }; +const char * const trampPowerNames_5G8_1600[VTX_TRAMP_5G8_MAX_POWER_COUNT + 1] = { "---", "25 ", "400", "800", "1600", "1600" }; + +const uint16_t trampPowerTable_5G8_5000[VTX_TRAMP_5G8_MAX_POWER_COUNT] = { 50, 500, 1000, 2500, 5000 }; +const char * const trampPowerNames_5G8_5000[VTX_TRAMP_5G8_MAX_POWER_COUNT + 1] = { "---", "25 ", "100", "200", "500", "5000" }; + const uint16_t trampPowerTable_1G3_800[VTX_TRAMP_1G3_MAX_POWER_COUNT] = { 25, 200, 800 }; const char * const trampPowerNames_1G3_800[VTX_TRAMP_1G3_MAX_POWER_COUNT + 1] = { "---", "25 ", "200", "800" }; @@ -610,6 +616,22 @@ static void vtxProtoUpdatePowerMetadata(uint16_t maxPower) impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_5G8_800; impl_vtxDevice.capability.powerCount = VTX_TRAMP_5G8_MAX_POWER_COUNT; } + else if (maxPower >= 5000) { + // Max power 5000mW: Use 50, 500, 1000, 2500, 5000 table + vtxState.metadata.powerTablePtr = trampPowerTable_5G8_5000; + vtxState.metadata.powerTableCount = VTX_TRAMP_5G8_MAX_POWER_COUNT; + + impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_5G8_5000; + impl_vtxDevice.capability.powerCount = VTX_TRAMP_5G8_MAX_POWER_COUNT; + } + else if (maxPower >= 1600) { + // Max power 1600mW: Use 25, 400, 800, 1600 table + vtxState.metadata.powerTablePtr = trampPowerTable_5G8_1600; + vtxState.metadata.powerTableCount = VTX_TRAMP_5G8_MAX_POWER_COUNT; + + impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_5G8_1600; + impl_vtxDevice.capability.powerCount = 4; + } else if (maxPower >= 600) { // Max power 600mW: Use 25, 100, 200, 400, 600 table vtxState.metadata.powerTablePtr = trampPowerTable_5G8_600;