Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update vtx_tramp.c for VTX #10180

Open
wants to merge 4 commits into
base: master
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
22 changes: 22 additions & 0 deletions src/main/io/vtx_tramp.c
Original file line number Diff line number Diff line change
Expand Up @@ -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" };

Expand Down Expand Up @@ -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;
Expand Down