Skip to content

Commit c2a8146

Browse files
Added IRC Tramp pseudo-vtx tables. Allows users to override configuration values
1 parent 2747993 commit c2a8146

File tree

4 files changed

+199
-47
lines changed

4 files changed

+199
-47
lines changed

src/main/config/parameter_group_ids.h

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -132,7 +132,8 @@
132132
#define PG_GEOZONE_CONFIG 1042
133133
#define PG_GEOZONES 1043
134134
#define PG_GEOZONE_VERTICES 1044
135-
#define PG_INAV_END PG_GEOZONE_VERTICES
135+
#define PG_TRAMP_TABLE_O_RIDE 1045
136+
#define PG_INAV_END PG_TRAMP_TABLE_O_RIDE
136137

137138
// OSD configuration (subject to change)
138139
//#define PG_OSD_FONT_CONFIG 2047

src/main/fc/cli.c

Lines changed: 78 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -95,6 +95,7 @@ bool cliMode = false;
9595
#include "io/osd.h"
9696
#include "io/osd/custom_elements.h"
9797
#include "io/serial.h"
98+
#include "io/vtx_tramp.h"
9899

99100
#include "fc/fc_msp_box.h"
100101

@@ -3220,6 +3221,74 @@ static void cliTimerOutputMode(char *cmdline)
32203221

32213222
}
32223223

3224+
static void printTrampConfig(char* cmdline)
3225+
{
3226+
(void) cmdline;
3227+
dumpLiveVtxTrampConfig(cliPrintf);
3228+
}
3229+
3230+
static void cliTrampPwOr(char *cmdline)
3231+
{
3232+
static const char parseErrString[] = "ERROR. Cannot parse tramp PL override.\n";
3233+
if(isEmpty(cmdline))
3234+
{
3235+
// Nothing sent, so fail and bail.
3236+
cliPrint(parseErrString);
3237+
return;
3238+
}
3239+
3240+
// Command structure is: <PL Override IDX> <Power_MW>
3241+
const char* current_cmd = cmdline++;
3242+
3243+
// Get the PL index.
3244+
int powerIdx = fastA2I(current_cmd);
3245+
if(powerIdx > VTX_TRAMP_MAX_SUPPORTED_PW_LEVELS || powerIdx < 1)
3246+
{
3247+
// Invalid range, fail and bail
3248+
cliPrint(parseErrString);
3249+
return;
3250+
}
3251+
3252+
// Convert PL Index to array indexable value
3253+
powerIdx--;
3254+
3255+
// Get the PL value.
3256+
int reqPlMw = VTX_TRAMP_NULL_PW_CONFIG;
3257+
current_cmd = nextArg(current_cmd);
3258+
if(current_cmd)
3259+
{
3260+
reqPlMw = fastA2I(current_cmd);
3261+
}
3262+
3263+
// If invalid, set to null (user may request that the VTX table is used as-is or it is not implemented)
3264+
if(reqPlMw < 0)
3265+
{
3266+
reqPlMw = VTX_TRAMP_NULL_PW_CONFIG;
3267+
}
3268+
3269+
cliPrintf("Tramp Override stat - PL IDX: %d; PL (mw): %d", powerIdx + 1, reqPlMw);
3270+
3271+
vtxTrampPwOverride_t* powerConfig = vtxTrampPwOverrideMutable(powerIdx);
3272+
powerConfig->vtxPwOverrideMw = reqPlMw;
3273+
}
3274+
3275+
static void printTrampOverride(uint8_t dumpMask, const vtxTrampPwOverride_t* trampOverrideConfig, const vtxTrampPwOverride_t* defaultTrampOverrideConfig)
3276+
{
3277+
const char* dumpFormat = VTX_TRAMP_PL_OR_CMD " %d %d";
3278+
for (uint32_t currentPwLvl = 0; currentPwLvl < VTX_TRAMP_MAX_SUPPORTED_PW_LEVELS; currentPwLvl++)
3279+
{
3280+
const vtxTrampPwOverride_t* current_config = &trampOverrideConfig[currentPwLvl];
3281+
bool equalsDefault = false;
3282+
if (defaultTrampOverrideConfig) {
3283+
const vtxTrampPwOverride_t* default_config = &defaultTrampOverrideConfig[currentPwLvl];
3284+
equalsDefault = current_config->vtxPwOverrideMw == default_config->vtxPwOverrideMw;
3285+
cliDefaultPrintLinef(dumpMask, equalsDefault, dumpFormat, currentPwLvl + 1, default_config->vtxPwOverrideMw);
3286+
}
3287+
3288+
cliDumpPrintLinef(dumpMask, equalsDefault, dumpFormat, currentPwLvl + 1, current_config->vtxPwOverrideMw);
3289+
}
3290+
}
3291+
32233292
static void printFeature(uint8_t dumpMask, const featureConfig_t *featureConfig, const featureConfig_t *featureConfigDefault)
32243293
{
32253294
uint32_t mask = featureConfig->enabledFeatures;
@@ -4531,6 +4600,11 @@ static void printConfig(const char *cmdline, bool doDiff)
45314600
printOsdLayout(dumpMask, &osdLayoutsConfig_Copy, osdLayoutsConfig(), -1, -1);
45324601
#endif
45334602

4603+
#ifdef USE_VTX_TRAMP
4604+
cliPrintHashLine("IRC Tramp VTX Table Overrides");
4605+
printTrampOverride(dumpMask, vtxTrampPwOverride_CopyArray, vtxTrampPwOverride(0));
4606+
#endif
4607+
45344608
#ifdef USE_PROGRAMMING_FRAMEWORK
45354609
cliPrintHashLine("Programming: logic");
45364610
printLogic(dumpMask, logicConditions_CopyArray, logicConditions(0), -1);
@@ -4942,6 +5016,10 @@ const clicmd_t cmdTable[] = {
49425016
CLI_COMMAND_DEF("osd_layout", "get or set the layout of OSD items", "[<layout> [<item> [<col> <row> [<visible>]]]]", cliOsdLayout),
49435017
#endif
49445018
CLI_COMMAND_DEF("timer_output_mode", "get or set the outputmode for a given timer.", "[<timer> [<AUTO|MOTORS|SERVOS>]]", cliTimerOutputMode),
5019+
#ifdef USE_VTX_TRAMP
5020+
CLI_COMMAND_DEF(VTX_TRAMP_PL_OR_CMD, "Set the power level override of an IRC tramp VTX table", NULL, cliTrampPwOr),
5021+
CLI_COMMAND_DEF(VTX_TRAMP_CONFIG_DUMP_CMD, "Dump the live operating tramp config", NULL, printTrampConfig),
5022+
#endif
49455023
};
49465024

49475025
static void cliHelp(char *cmdline)

src/main/io/vtx_tramp.c

Lines changed: 99 additions & 46 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
#include <stdint.h>
2525
#include <ctype.h>
2626
#include <string.h>
27+
#include <stdio.h>
2728

2829
#include "platform.h"
2930

@@ -42,6 +43,8 @@
4243
#include "io/vtx_control.h"
4344
#include "io/vtx.h"
4445
#include "io/vtx_string.h"
46+
#include "config/parameter_group_ids.h"
47+
#include "config/config_reset.h"
4548

4649
#define VTX_PKT_SIZE 16
4750
#define VTX_PROTO_STATE_TIMEOUT_MS 1000
@@ -52,6 +55,18 @@
5255
#define VTX_UPDATE_REQ_POWER 0x02
5356
#define VTX_UPDATE_REQ_PITMODE 0x04
5457

58+
PG_REGISTER_ARRAY_WITH_RESET_FN(vtxTrampPwOverride_t, VTX_TRAMP_MAX_SUPPORTED_PW_LEVELS, vtxTrampPwOverride, PG_TRAMP_TABLE_O_RIDE, VTX_TRAMP_PW_OVERRIDE_VER);
59+
60+
void pgResetFn_vtxTrampPwOverride(vtxTrampPwOverride_t* table)
61+
{
62+
for (int current_pw_lvl = 0; current_pw_lvl < VTX_TRAMP_MAX_SUPPORTED_PW_LEVELS; current_pw_lvl++)
63+
{
64+
RESET_CONFIG(vtxTrampPwOverride_t, &table[current_pw_lvl],
65+
.vtxPwOverrideMw = -1
66+
);
67+
}
68+
}
69+
5570
typedef enum {
5671
VTX_STATE_RESET = 0,
5772
VTX_STATE_OFFILE = 1, // Not detected
@@ -560,41 +575,99 @@ static vtxDevice_t impl_vtxDevice = {
560575
.capability.powerNames = NULL,
561576
};
562577

563-
const uint16_t trampPowerTable_5G8_200[VTX_TRAMP_5G8_MAX_POWER_COUNT] = { 25, 100, 200, 200, 200 };
564-
const char * const trampPowerNames_5G8_200[VTX_TRAMP_5G8_MAX_POWER_COUNT + 1] = { "---", "25 ", "100", "200", "200", "200" };
578+
// Backwards compatable mutable data structures to allow for configuration to be added.
579+
static uint16_t mutableTablePowers[VTX_TRAMP_MAX_SUPPORTED_PW_LEVELS];
580+
#define MAX_VTX_PWR_NAME_CHARS 6
581+
static char mutableTablePowerNames[VTX_TRAMP_MAX_SUPPORTED_PW_LEVELS + 1][MAX_VTX_PWR_NAME_CHARS];
565582

583+
// Default table power levels
584+
const uint16_t trampPowerTable_5G8_200[VTX_TRAMP_5G8_MAX_POWER_COUNT] = { 25, 100, 200, 200, 200 };
566585
const uint16_t trampPowerTable_5G8_400[VTX_TRAMP_5G8_MAX_POWER_COUNT] = { 25, 100, 200, 400, 400 };
567-
const char * const trampPowerNames_5G8_400[VTX_TRAMP_5G8_MAX_POWER_COUNT + 1] = { "---", "25 ", "100", "200", "400", "400" };
568-
569586
const uint16_t trampPowerTable_5G8_600[VTX_TRAMP_5G8_MAX_POWER_COUNT] = { 25, 100, 200, 400, 600 };
570-
const char * const trampPowerNames_5G8_600[VTX_TRAMP_5G8_MAX_POWER_COUNT + 1] = { "---", "25 ", "100", "200", "400", "600" };
571-
572587
const uint16_t trampPowerTable_5G8_800[VTX_TRAMP_5G8_MAX_POWER_COUNT] = { 25, 100, 200, 500, 800 };
573-
const char * const trampPowerNames_5G8_800[VTX_TRAMP_5G8_MAX_POWER_COUNT + 1] = { "---", "25 ", "100", "200", "500", "800" };
574-
575588
const uint16_t trampPowerTable_1G3_800[VTX_TRAMP_1G3_MAX_POWER_COUNT] = { 25, 200, 800 };
576-
const char * const trampPowerNames_1G3_800[VTX_TRAMP_1G3_MAX_POWER_COUNT + 1] = { "---", "25 ", "200", "800" };
589+
const uint16_t trampPowerTable_1G3_2000[VTX_TRAMP_1G3_MAX_POWER_COUNT] = { 25, 200, 2000 };
590+
591+
// Dump the VTX operating params to the console. Used for configuration validation to ensure that the VTX is being commanded as
592+
// expected. Used to debug VTX issues such as inconsistent power levels (IE command 1 mw for first power, 2 mw for second, etc),
593+
// frequency issues (commanded != requested), etc. This does require that the CLI serial interface is exposed, but better that than
594+
// exposing the VTX driver internals to the CLI.
595+
void dumpLiveVtxTrampConfig(consolePrintf_t consolePrint)
596+
{
597+
// Dump configuration
598+
consolePrint("Configured power levels: %d\n", impl_vtxDevice.capability.powerCount);
599+
for(uint8_t current_pl = 0; current_pl < VTX_TRAMP_MAX_SUPPORTED_PW_LEVELS; current_pl++)
600+
{
601+
consolePrint("PL %d: %d mw\n", current_pl + 1, mutableTablePowers[current_pl]);
602+
}
577603

578-
const uint16_t trampPowerTable_1G3_2000[VTX_TRAMP_1G3_MAX_POWER_COUNT] = { 25, 200, 2000 };
579-
const char * const trampPowerNames_1G3_2000[VTX_TRAMP_1G3_MAX_POWER_COUNT + 1] = { "---", "25 ", "200", "2000" };
604+
consolePrint("Actual VTX Freq: %u\n", vtxState.state.freq);
605+
consolePrint("Actual VTX Power: %u\n", vtxState.state.power);
606+
607+
consolePrint("Requested VTX Freq: %u\n", vtxState.request.freq);
608+
consolePrint("Requested VTX Power: %u\n", vtxState.request.power);
609+
consolePrint("Requested VTX Power IDX: %u\n", vtxState.request.powerIndex);
610+
}
611+
612+
// Construct the power table. Takes into account any configured override power values.
613+
// baseTable - Pointer to the base table configuration
614+
// tableCount - Entries in the table configuration
615+
static void constructPowerTable(const uint16_t* baseTable, const uint16_t tableCount)
616+
{
617+
// Update the 0th power index
618+
strcpy(mutableTablePowerNames[0], "---");
619+
620+
// Now construct each table
621+
const vtxTrampPwOverride_t* pwr_config;
622+
uint16_t currentPwLvl = 0;
623+
for(currentPwLvl = 0; currentPwLvl < VTX_TRAMP_MAX_SUPPORTED_PW_LEVELS; currentPwLvl++)
624+
{
625+
pwr_config = vtxTrampPwOverride(currentPwLvl);
626+
if(pwr_config->vtxPwOverrideMw >= 0)
627+
{
628+
// Only override if power is configured to a valid value. If negative, this value is not configured and
629+
// will be set to the default table for the power level.
630+
mutableTablePowers[currentPwLvl] = (uint16_t) pwr_config->vtxPwOverrideMw;
631+
}
632+
633+
else if(currentPwLvl < tableCount)
634+
{
635+
// Not configured, so use the default.
636+
mutableTablePowers[currentPwLvl] = *(baseTable + currentPwLvl);
637+
}
638+
else
639+
{
640+
// No default value and no configured value. Nothing to write, so terminate from the loop.
641+
break;
642+
}
643+
644+
// Update the "stringified" power. Always add 1 to the working power level since 0 is reserved.
645+
sprintf(mutableTablePowerNames[currentPwLvl + 1], "%u", mutableTablePowers[currentPwLvl]);
646+
}
647+
648+
// Update the stored params.
649+
vtxState.metadata.powerTablePtr = mutableTablePowers;
650+
651+
// NOTE: If loop broke before max (IE 2 overrides and three default, < 5, idx = 3) the last loop index will be the total
652+
// quantity configured. Set that here.
653+
vtxState.metadata.powerTableCount = currentPwLvl;
654+
655+
impl_vtxDevice.capability.powerNames = (char**) mutableTablePowerNames;
656+
impl_vtxDevice.capability.powerCount = currentPwLvl;
657+
658+
// NOTE: If less power levels than max supported are passed, then the upper values in the config are left as-is.
659+
// The result is that they are not used.
660+
}
580661

581662
static void vtxProtoUpdatePowerMetadata(uint16_t maxPower)
582663
{
583664
switch (vtxSettingsConfig()->frequencyGroup) {
584665
case FREQUENCYGROUP_1G3:
585666
if (maxPower >= 2000) {
586-
vtxState.metadata.powerTablePtr = trampPowerTable_1G3_2000;
587-
vtxState.metadata.powerTableCount = VTX_TRAMP_1G3_MAX_POWER_COUNT;
588-
589-
impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_1G3_2000;
590-
impl_vtxDevice.capability.powerCount = VTX_TRAMP_1G3_MAX_POWER_COUNT;
667+
constructPowerTable(trampPowerTable_1G3_2000, VTX_TRAMP_1G3_MAX_POWER_COUNT);
591668
}
592669
else {
593-
vtxState.metadata.powerTablePtr = trampPowerTable_1G3_800;
594-
vtxState.metadata.powerTableCount = VTX_TRAMP_1G3_MAX_POWER_COUNT;
595-
596-
impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_1G3_800;
597-
impl_vtxDevice.capability.powerCount = VTX_TRAMP_1G3_MAX_POWER_COUNT;
670+
constructPowerTable(trampPowerTable_1G3_800, VTX_TRAMP_1G3_MAX_POWER_COUNT);
598671
}
599672
impl_vtxDevice.capability.bandCount = VTX_TRAMP_1G3_BAND_COUNT;
600673
impl_vtxDevice.capability.channelCount = VTX_TRAMP_1G3_CHANNEL_COUNT;
@@ -604,43 +677,23 @@ static void vtxProtoUpdatePowerMetadata(uint16_t maxPower)
604677
default:
605678
if (maxPower >= 800) {
606679
// Max power 800mW: Use 25, 100, 200, 500, 800 table
607-
vtxState.metadata.powerTablePtr = trampPowerTable_5G8_800;
608-
vtxState.metadata.powerTableCount = VTX_TRAMP_5G8_MAX_POWER_COUNT;
609-
610-
impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_5G8_800;
611-
impl_vtxDevice.capability.powerCount = VTX_TRAMP_5G8_MAX_POWER_COUNT;
680+
constructPowerTable(trampPowerTable_5G8_800, sizeof(trampPowerTable_5G8_800)/sizeof(trampPowerTable_5G8_800[0]));
612681
}
613682
else if (maxPower >= 600) {
614683
// Max power 600mW: Use 25, 100, 200, 400, 600 table
615-
vtxState.metadata.powerTablePtr = trampPowerTable_5G8_600;
616-
vtxState.metadata.powerTableCount = VTX_TRAMP_5G8_MAX_POWER_COUNT;
617-
618-
impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_5G8_600;
619-
impl_vtxDevice.capability.powerCount = VTX_TRAMP_5G8_MAX_POWER_COUNT;
684+
constructPowerTable(trampPowerTable_5G8_600, sizeof(trampPowerTable_5G8_600)/sizeof(trampPowerTable_5G8_600[0]));
620685
}
621686
else if (maxPower >= 400) {
622687
// Max power 400mW: Use 25, 100, 200, 400 table
623-
vtxState.metadata.powerTablePtr = trampPowerTable_5G8_400;
624-
vtxState.metadata.powerTableCount = 4;
625-
626-
impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_5G8_400;
627-
impl_vtxDevice.capability.powerCount = 4;
688+
constructPowerTable(trampPowerTable_5G8_400, sizeof(trampPowerTable_5G8_400)/sizeof(trampPowerTable_5G8_400[0]));
628689
}
629690
else if (maxPower >= 200) {
630691
// Max power 200mW: Use 25, 100, 200 table
631-
vtxState.metadata.powerTablePtr = trampPowerTable_5G8_200;
632-
vtxState.metadata.powerTableCount = 3;
633-
634-
impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_5G8_200;
635-
impl_vtxDevice.capability.powerCount = 3;
692+
constructPowerTable(trampPowerTable_5G8_200, sizeof(trampPowerTable_5G8_200)/sizeof(trampPowerTable_5G8_200[0]));
636693
}
637694
else {
638695
// Default to standard TRAMP 600mW VTX
639-
vtxState.metadata.powerTablePtr = trampPowerTable_5G8_600;
640-
vtxState.metadata.powerTableCount = VTX_TRAMP_5G8_MAX_POWER_COUNT;
641-
642-
impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_5G8_600;
643-
impl_vtxDevice.capability.powerCount = VTX_TRAMP_5G8_MAX_POWER_COUNT;
696+
constructPowerTable(trampPowerTable_5G8_600, sizeof(trampPowerTable_5G8_600)/sizeof(trampPowerTable_5G8_600[0]));
644697
}
645698
break;
646699
}

src/main/io/vtx_tramp.h

Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#pragma once
1919

2020
#include <stdint.h>
21+
#include "config/parameter_group.h"
2122

2223
// 5.8 GHz
2324
#define VTX_TRAMP_5G8_BAND_COUNT 5
@@ -39,4 +40,23 @@
3940
#define VTX_TRAMP_1G3_MIN_FREQUENCY_MHZ 1000
4041
#define VTX_TRAMP_1G3_MAX_FREQUENCY_MHZ 1399
4142

43+
// Defines a 'zero' config value.
44+
#define VTX_TRAMP_NULL_PW_CONFIG -1
45+
46+
#define VTX_TRAMP_MAX_SUPPORTED_PW_LEVELS VTX_TRAMP_5G8_MAX_POWER_COUNT
47+
#define VTX_TRAMP_PW_OVERRIDE_VER 1
48+
49+
#define VTX_TRAMP_PL_OR_CMD "tramp_pl_override"
50+
#define VTX_TRAMP_CONFIG_DUMP_CMD "tramp_dump_config"
51+
52+
typedef struct {
53+
int vtxPwOverrideMw;
54+
} vtxTrampPwOverride_t;
55+
56+
PG_DECLARE_ARRAY(vtxTrampPwOverride_t, VTX_TRAMP_MAX_SUPPORTED_PW_LEVELS, vtxTrampPwOverride);
57+
4258
bool vtxTrampInit(void);
59+
60+
typedef void (*consolePrintf_t)(const char*, ...);
61+
62+
void dumpLiveVtxTrampConfig(consolePrintf_t consolePrint);

0 commit comments

Comments
 (0)