mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 20:35:33 +03:00
[VTX] vtxTable factory flag and full integration of vtxTable (#8380)
Moved vtxtable frequency mode implementation into `vtx_common.c`. This makes the implementation available for all vtx types and allows for some code deduplication (see point below) Removed band and channel tracking from tramp and rtc6705. The hardware underlying both only support frequency mode and the tracking is now done in `vtx_common.c` using the new factory flag. Deleted vtxStringXXX. to continue supporting builds without `USE_VTX_TABLE`, new infrastructure was created in `drivers/vtx_table.c`, which loads fixed tables into vtxTableXXX when built witout `USE_VTX_TABLE`. Individual vtx implementations no longer need to load any band/channel tables. They only need to load their individual power tables when built without `USE_VTX_TABLE`. Additionally this allows for the next point: Fully integrated vtxTableXXX and removed the old and no longer needed indirection of frequency and power tables in `vtxDevice_t`. Removed VTX_SETTINGS_* constants from `vtx_common.h` and replaced them with the vtxtable equivalent. rtc6705 implementation now uses power values from vtxtable instead of using indices directly. It also stops using index 0. This makes it consistent with other vtx implementations and is more user configurable. It also cleans up `telemetry\srxl.c` which had to have a special case for rtc6705. Finally, frequency entries in the vtxtable can now be marked as empty by setting their frequency to 0. Betaflight will never allow a blocked channel to be selected. This is useful for vtxtable index mode (FACTORY flag set) where manufacturer-defined bands can be truncated to ensure compliance with local laws and regulations.
This commit is contained in:
parent
9abf63a0b0
commit
7cb34205b3
29 changed files with 516 additions and 591 deletions
|
@ -170,7 +170,6 @@ COMMON_SRC = \
|
|||
telemetry/ibus.c \
|
||||
telemetry/ibus_shared.c \
|
||||
sensors/esc_sensor.c \
|
||||
io/vtx_string.c \
|
||||
io/vtx.c \
|
||||
io/vtx_rtc6705.c \
|
||||
io/vtx_smartaudio.c \
|
||||
|
@ -319,7 +318,6 @@ SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
|
|||
cms/cms_menu_vtx_rtc6705.c \
|
||||
cms/cms_menu_vtx_smartaudio.c \
|
||||
cms/cms_menu_vtx_tramp.c \
|
||||
io/vtx_string.c \
|
||||
io/vtx.c \
|
||||
io/vtx_rtc6705.c \
|
||||
io/vtx_smartaudio.c \
|
||||
|
|
|
@ -2447,8 +2447,7 @@ static void cliVtx(char *cmdline)
|
|||
ptr = nextArg(ptr);
|
||||
if (ptr) {
|
||||
val = atoi(ptr);
|
||||
// FIXME Use VTX API to get max
|
||||
if (val >= 0 && val <= VTX_SETTINGS_MAX_BAND) {
|
||||
if (val >= 0 && val <= vtxTableBandCount) {
|
||||
cac->band = val;
|
||||
validArgumentCount++;
|
||||
}
|
||||
|
@ -2456,8 +2455,7 @@ static void cliVtx(char *cmdline)
|
|||
ptr = nextArg(ptr);
|
||||
if (ptr) {
|
||||
val = atoi(ptr);
|
||||
// FIXME Use VTX API to get max
|
||||
if (val >= 0 && val <= VTX_SETTINGS_MAX_CHANNEL) {
|
||||
if (val >= 0 && val <= vtxTableChannelCount) {
|
||||
cac->channel = val;
|
||||
validArgumentCount++;
|
||||
}
|
||||
|
@ -2465,8 +2463,7 @@ static void cliVtx(char *cmdline)
|
|||
ptr = nextArg(ptr);
|
||||
if (ptr) {
|
||||
val = atoi(ptr);
|
||||
// FIXME Use VTX API to get max
|
||||
if (val >= 0 && val < VTX_SETTINGS_POWER_COUNT) {
|
||||
if (val >= 0 && val < vtxTablePowerLevels) {
|
||||
cac->power= val;
|
||||
validArgumentCount++;
|
||||
}
|
||||
|
@ -2497,11 +2494,12 @@ static void cliVtx(char *cmdline)
|
|||
|
||||
#ifdef USE_VTX_TABLE
|
||||
|
||||
static char *formatVtxTableBandFrequency(const uint16_t *frequency, int channels)
|
||||
static char *formatVtxTableBandFrequency(const bool isFactory, const uint16_t *frequency, int channels)
|
||||
{
|
||||
static char freqbuf[5 * VTX_TABLE_MAX_CHANNELS + 1];
|
||||
static char freqbuf[5 * VTX_TABLE_MAX_CHANNELS + 8 + 1];
|
||||
char freqtmp[5 + 1];
|
||||
freqbuf[0] = 0;
|
||||
strcat(freqbuf, isFactory ? " FACTORY" : " CUSTOM ");
|
||||
for (int channel = 0; channel < channels; channel++) {
|
||||
tfp_sprintf(freqtmp, " %4d", frequency[channel]);
|
||||
strcat(freqbuf, freqtmp);
|
||||
|
@ -2528,11 +2526,11 @@ static const char *printVtxTableBand(dumpFlags_t dumpMask, int band, const vtxTa
|
|||
}
|
||||
}
|
||||
headingStr = cliPrintSectionHeading(dumpMask, !equalsDefault, headingStr);
|
||||
char *freqbuf = formatVtxTableBandFrequency(defaultConfig->frequency[band], defaultConfig->channels);
|
||||
char *freqbuf = formatVtxTableBandFrequency(defaultConfig->isFactoryBand[band], defaultConfig->frequency[band], defaultConfig->channels);
|
||||
cliDefaultPrintLinef(dumpMask, equalsDefault, fmt, band + 1, defaultConfig->bandNames[band], defaultConfig->bandLetters[band], freqbuf);
|
||||
}
|
||||
|
||||
char *freqbuf = formatVtxTableBandFrequency(currentConfig->frequency[band], currentConfig->channels);
|
||||
char *freqbuf = formatVtxTableBandFrequency(currentConfig->isFactoryBand[band], currentConfig->frequency[band], currentConfig->channels);
|
||||
cliDumpPrintLinef(dumpMask, equalsDefault, fmt, band + 1, currentConfig->bandNames[band], currentConfig->bandLetters[band], freqbuf);
|
||||
return headingStr;
|
||||
}
|
||||
|
@ -2817,8 +2815,20 @@ static void cliVtxTable(char *cmdline)
|
|||
uint16_t bandfreq[VTX_TABLE_MAX_CHANNELS];
|
||||
int channel = 0;
|
||||
int channels = vtxTableConfigMutable()->channels;
|
||||
bool isFactory = false;
|
||||
|
||||
for (channel = 0; channel < channels && (tok = strtok_r(NULL, " ", &saveptr)); channel++) {
|
||||
if (channel == 0 && !isdigit(tok[0])) {
|
||||
channel -= 1;
|
||||
if (strcasecmp(tok, "FACTORY") == 0) {
|
||||
isFactory = true;
|
||||
} else if (strcasecmp(tok, "CUSTOM") == 0) {
|
||||
isFactory = false;
|
||||
} else {
|
||||
cliPrintErrorLinef("INVALID FACTORY FLAG %s (EXPECTED FACTORY OR CUSTOM)", tok);
|
||||
return;
|
||||
}
|
||||
}
|
||||
int freq = atoi(tok);
|
||||
if (freq < 0) {
|
||||
cliPrintErrorLinef("INVALID FREQUENCY %s", tok);
|
||||
|
@ -2841,6 +2851,7 @@ static void cliVtxTable(char *cmdline)
|
|||
for (int i = 0; i < channel; i++) {
|
||||
vtxTableConfigMutable()->frequency[band][i] = bandfreq[i];
|
||||
}
|
||||
vtxTableConfigMutable()->isFactoryBand[band] = isFactory;
|
||||
} else {
|
||||
// Bad subcommand
|
||||
cliPrintErrorLinef("INVALID SUBCOMMAND %s", tok);
|
||||
|
@ -5999,7 +6010,7 @@ const clicmd_t cmdTable[] = {
|
|||
#endif
|
||||
#endif
|
||||
#ifdef USE_VTX_TABLE
|
||||
CLI_COMMAND_DEF("vtxtable", "vtx frequency able", "<band> <bandname> <bandletter> <freq> ... <freq>\r\n", cliVtxTable),
|
||||
CLI_COMMAND_DEF("vtxtable", "vtx frequency able", "<band> <bandname> <bandletter> [FACTORY|CUSTOM] <freq> ... <freq>\r\n", cliVtxTable),
|
||||
#endif
|
||||
};
|
||||
|
||||
|
|
|
@ -39,6 +39,7 @@
|
|||
#include "drivers/light_led.h"
|
||||
#include "drivers/pinio.h"
|
||||
#include "drivers/vtx_common.h"
|
||||
#include "drivers/vtx_table.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
|
@ -1316,9 +1317,9 @@ const clivalue_t valueTable[] = {
|
|||
|
||||
// PG_VTX_CONFIG
|
||||
#ifdef USE_VTX_COMMON
|
||||
{ "vtx_band", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { VTX_SETTINGS_NO_BAND, VTX_SETTINGS_MAX_BAND }, PG_VTX_SETTINGS_CONFIG, offsetof(vtxSettingsConfig_t, band) },
|
||||
{ "vtx_channel", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { VTX_SETTINGS_MIN_CHANNEL, VTX_SETTINGS_MAX_CHANNEL }, PG_VTX_SETTINGS_CONFIG, offsetof(vtxSettingsConfig_t, channel) },
|
||||
{ "vtx_power", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { VTX_SETTINGS_MIN_POWER, VTX_SETTINGS_POWER_COUNT-1 }, PG_VTX_SETTINGS_CONFIG, offsetof(vtxSettingsConfig_t, power) },
|
||||
{ "vtx_band", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, VTX_TABLE_MAX_BANDS }, PG_VTX_SETTINGS_CONFIG, offsetof(vtxSettingsConfig_t, band) },
|
||||
{ "vtx_channel", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, VTX_TABLE_MAX_CHANNELS }, PG_VTX_SETTINGS_CONFIG, offsetof(vtxSettingsConfig_t, channel) },
|
||||
{ "vtx_power", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, VTX_TABLE_MAX_POWER_LEVELS - 1 }, PG_VTX_SETTINGS_CONFIG, offsetof(vtxSettingsConfig_t, power) },
|
||||
{ "vtx_low_power_disarm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_VTX_LOW_POWER_DISARM }, PG_VTX_SETTINGS_CONFIG, offsetof(vtxSettingsConfig_t, lowPowerDisarm) },
|
||||
#ifdef VTX_SETTINGS_FREQCMD
|
||||
{ "vtx_freq", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, VTX_SETTINGS_MAX_FREQUENCY_MHZ }, PG_VTX_SETTINGS_CONFIG, offsetof(vtxSettingsConfig_t, freq) },
|
||||
|
|
|
@ -21,6 +21,7 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <ctype.h>
|
||||
#include <drivers/vtx_table.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
|
@ -36,7 +37,6 @@
|
|||
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "io/vtx_string.h"
|
||||
#include "io/vtx_rtc6705.h"
|
||||
#include "io/vtx.h"
|
||||
|
||||
|
@ -45,23 +45,22 @@ static uint8_t cmsx_vtxChannel;
|
|||
static uint8_t cmsx_vtxPower;
|
||||
|
||||
static OSD_TAB_t entryVtxBand;
|
||||
static OSD_UINT8_t entryVtxChannel;
|
||||
static OSD_TAB_t entryVtxChannel;
|
||||
static OSD_TAB_t entryVtxPower;
|
||||
|
||||
static void cmsx_Vtx_ConfigRead(void)
|
||||
{
|
||||
cmsx_vtxBand = vtxSettingsConfig()->band - 1;
|
||||
cmsx_vtxChannel = vtxSettingsConfig()->channel;
|
||||
cmsx_vtxPower = vtxSettingsConfig()->power - VTX_RTC6705_MIN_POWER;
|
||||
vtxCommonGetBandAndChannel(vtxCommonDevice(), &cmsx_vtxBand, &cmsx_vtxChannel);
|
||||
vtxCommonGetPowerIndex(vtxCommonDevice(), &cmsx_vtxPower);
|
||||
}
|
||||
|
||||
static void cmsx_Vtx_ConfigWriteback(void)
|
||||
{
|
||||
// update vtx_ settings
|
||||
vtxSettingsConfigMutable()->band = cmsx_vtxBand + 1;
|
||||
vtxSettingsConfigMutable()->band = cmsx_vtxBand;
|
||||
vtxSettingsConfigMutable()->channel = cmsx_vtxChannel;
|
||||
vtxSettingsConfigMutable()->power = cmsx_vtxPower + VTX_RTC6705_MIN_POWER;
|
||||
vtxSettingsConfigMutable()->freq = vtxCommonLookupFrequency(vtxCommonDevice(), cmsx_vtxBand + 1, cmsx_vtxChannel);
|
||||
vtxSettingsConfigMutable()->power = cmsx_vtxPower;
|
||||
vtxSettingsConfigMutable()->freq = vtxCommonLookupFrequency(vtxCommonDevice(), cmsx_vtxBand, cmsx_vtxChannel);
|
||||
|
||||
saveConfigAndNotify();
|
||||
}
|
||||
|
@ -70,20 +69,17 @@ static long cmsx_Vtx_onEnter(void)
|
|||
{
|
||||
cmsx_Vtx_ConfigRead();
|
||||
|
||||
vtxDevice_t *device = vtxCommonDevice();
|
||||
|
||||
entryVtxBand.val = &cmsx_vtxBand;
|
||||
entryVtxBand.max = device->capability.bandCount - 1;
|
||||
entryVtxBand.names = &device->bandNames[1];
|
||||
entryVtxBand.max = vtxTableBandCount;
|
||||
entryVtxBand.names = vtxTableBandNames;
|
||||
|
||||
entryVtxChannel.val = &cmsx_vtxChannel;
|
||||
entryVtxChannel.min = 1;
|
||||
entryVtxChannel.max = device->capability.channelCount;
|
||||
entryVtxChannel.step = 1;
|
||||
entryVtxChannel.max = vtxTableChannelCount;
|
||||
entryVtxChannel.names = vtxTableChannelNames;
|
||||
|
||||
entryVtxPower.val = &cmsx_vtxPower;
|
||||
entryVtxPower.max = device->capability.powerCount - 1;
|
||||
entryVtxPower.names = device->powerNames;
|
||||
entryVtxPower.max = vtxTablePowerLevels;
|
||||
entryVtxPower.names = vtxTablePowerLabels;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
@ -97,13 +93,41 @@ static long cmsx_Vtx_onExit(const OSD_Entry *self)
|
|||
return 0;
|
||||
}
|
||||
|
||||
|
||||
static const OSD_Entry cmsx_menuVtxEntries[] =
|
||||
static long cmsx_Vtx_onBandChange(displayPort_t *pDisp, const void *self)
|
||||
{
|
||||
UNUSED(pDisp);
|
||||
UNUSED(self);
|
||||
if (cmsx_vtxBand == 0) {
|
||||
cmsx_vtxBand = 1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
static long cmsx_Vtx_onChanChange(displayPort_t *pDisp, const void *self)
|
||||
{
|
||||
UNUSED(pDisp);
|
||||
UNUSED(self);
|
||||
if (cmsx_vtxChannel == 0) {
|
||||
cmsx_vtxChannel = 1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
static long cmsx_Vtx_onPowerChange(displayPort_t *pDisp, const void *self)
|
||||
{
|
||||
UNUSED(pDisp);
|
||||
UNUSED(self);
|
||||
if (cmsx_vtxPower == 0) {
|
||||
cmsx_vtxPower = 1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
static const OSD_Entry cmsx_menuVtxEntries[] = {
|
||||
{"--- VTX ---", OME_Label, NULL, NULL, 0},
|
||||
{"BAND", OME_TAB, NULL, &entryVtxBand, 0},
|
||||
{"CHANNEL", OME_UINT8, NULL, &entryVtxChannel, 0},
|
||||
{"POWER", OME_TAB, NULL, &entryVtxPower, 0},
|
||||
{"BAND", OME_TAB, cmsx_Vtx_onBandChange, &entryVtxBand, 0},
|
||||
{"CHANNEL", OME_TAB, cmsx_Vtx_onChanChange, &entryVtxChannel, 0},
|
||||
{"POWER", OME_TAB, cmsx_Vtx_onPowerChange, &entryVtxPower, 0},
|
||||
{"BACK", OME_Back, NULL, NULL, 0},
|
||||
{NULL, OME_END, NULL, NULL, 0}
|
||||
};
|
||||
|
@ -114,7 +138,7 @@ CMS_Menu cmsx_menuVtxRTC6705 = {
|
|||
.GUARD_type = OME_MENU,
|
||||
#endif
|
||||
.onEnter = cmsx_Vtx_onEnter,
|
||||
.onExit= cmsx_Vtx_onExit,
|
||||
.onExit = cmsx_Vtx_onExit,
|
||||
.entries = cmsx_menuVtxEntries
|
||||
};
|
||||
|
||||
|
|
|
@ -22,6 +22,7 @@
|
|||
#include <stdint.h>
|
||||
#include <ctype.h>
|
||||
#include <string.h>
|
||||
#include <drivers/vtx_table.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
|
@ -38,7 +39,6 @@
|
|||
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "io/vtx_string.h"
|
||||
#include "io/vtx_smartaudio.h"
|
||||
#include "io/vtx.h"
|
||||
|
||||
|
@ -89,7 +89,7 @@ void saCmsUpdate(void)
|
|||
// This is a first valid response to GET_SETTINGS.
|
||||
saCmsOpmodel = saDevice.willBootIntoPitMode ? SACMS_OPMODEL_RACE : SACMS_OPMODEL_FREE;
|
||||
|
||||
saCmsFselMode = (saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ) ? 1 : 0;
|
||||
saCmsFselMode = (saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ) && vtxSettingsConfig()->band == 0 ? 1 : 0;
|
||||
|
||||
saCmsBand = vtxSettingsConfig()->band;
|
||||
saCmsChan = vtxSettingsConfig()->channel;
|
||||
|
@ -134,41 +134,45 @@ void saUpdateStatusString(void)
|
|||
return;
|
||||
|
||||
// XXX These should be done somewhere else
|
||||
if (saCmsDeviceStatus == 0 && saDevice.version != 0)
|
||||
if (saCmsDeviceStatus == 0 && saDevice.version != 0)
|
||||
saCmsDeviceStatus = saDevice.version;
|
||||
if (saCmsORFreq == 0 && saDevice.orfreq != 0)
|
||||
if (saCmsORFreq == 0 && saDevice.orfreq != 0)
|
||||
saCmsORFreq = saDevice.orfreq;
|
||||
if (saCmsUserFreq == 0 && saDevice.freq != 0)
|
||||
if (saCmsUserFreq == 0 && saDevice.freq != 0)
|
||||
saCmsUserFreq = saDevice.freq;
|
||||
|
||||
if (saDevice.version == 2) {
|
||||
if (saDevice.version == 2) {
|
||||
if (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE)
|
||||
saCmsPitFMode = 1;
|
||||
else
|
||||
saCmsPitFMode = 0;
|
||||
} else if (saDevice.version == 3) {
|
||||
} else if (saDevice.version == 3) {
|
||||
saCmsPitFMode = 1;//V2.1 only supports PIR
|
||||
}
|
||||
}
|
||||
|
||||
const vtxDevice_t *device = vtxCommonDevice();
|
||||
|
||||
saCmsStatusString[0] = "-FR"[saCmsOpmodel];
|
||||
|
||||
if (saCmsFselMode == 0) {
|
||||
saCmsStatusString[2] = vtxCommonLookupBandLetter(device, saDevice.channel / 8 + 1);
|
||||
saCmsStatusString[3] = vtxCommonLookupChannelName(device, (saDevice.channel % 8) + 1)[0];
|
||||
uint8_t band;
|
||||
uint8_t channel;
|
||||
vtxCommonGetBandAndChannel(device, &band, &channel);
|
||||
saCmsStatusString[2] = vtxCommonLookupBandLetter(device, band);
|
||||
saCmsStatusString[3] = vtxCommonLookupChannelName(device, channel)[0];
|
||||
} else {
|
||||
saCmsStatusString[2] = 'U';
|
||||
saCmsStatusString[3] = 'F';
|
||||
}
|
||||
|
||||
if ((saDevice.mode & SA_MODE_GET_PITMODE)
|
||||
&& (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE))
|
||||
&& (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE)) {
|
||||
tfp_sprintf(&saCmsStatusString[5], "%4d", saDevice.orfreq);
|
||||
else if (saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ)
|
||||
tfp_sprintf(&saCmsStatusString[5], "%4d", saDevice.freq);
|
||||
else
|
||||
tfp_sprintf(&saCmsStatusString[5], "%4d", vtxCommonLookupFrequency(vtxCommonDevice(), saDevice.channel / 8 + 1, saDevice.channel % 8 + 1));
|
||||
} else {
|
||||
uint16_t freq = 0;
|
||||
vtxCommonGetFrequency(device, &freq);
|
||||
tfp_sprintf(&saCmsStatusString[5], "%4d", freq);
|
||||
}
|
||||
|
||||
saCmsStatusString[9] = ' ';
|
||||
|
||||
|
@ -185,14 +189,13 @@ if (saDevice.version == 2) {
|
|||
} else {
|
||||
saCmsPit = 1;
|
||||
uint8_t powerIndex = 0;
|
||||
bool powerFound = vtxCommonGetPowerIndex(vtxCommonDevice(), &powerIndex);
|
||||
tfp_sprintf(&saCmsStatusString[10], "%s", powerFound ? vtxCommonLookupPowerName(vtxCommonDevice(), powerIndex) : "???");
|
||||
bool powerFound = vtxCommonGetPowerIndex(device, &powerIndex);
|
||||
tfp_sprintf(&saCmsStatusString[10], "%s", powerFound ? vtxCommonLookupPowerName(device, powerIndex) : "???");
|
||||
}
|
||||
#if defined(USE_VTX_TABLE)
|
||||
if (vtxCommonDevice()->capability.bandCount == 0 || vtxCommonDevice()->capability.powerCount == 0) {
|
||||
|
||||
if (vtxTableBandCount == 0 || vtxTablePowerLevels == 0) {
|
||||
strncpy(saCmsStatusString, "PLEASE CONFIGURE VTXTABLE", sizeof(saCmsStatusString));
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void saCmsResetOpmodel()
|
||||
|
@ -218,8 +221,9 @@ static long saCmsConfigBandByGvar(displayPort_t *pDisp, const void *self)
|
|||
return 0;
|
||||
}
|
||||
|
||||
if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred)
|
||||
saSetBandAndChannel(saCmsBand - 1, saCmsChan - 1);
|
||||
if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred) {
|
||||
vtxCommonSetBandAndChannel(vtxCommonDevice(), saCmsBand, saCmsChan);
|
||||
}
|
||||
|
||||
saCmsFreqRef = vtxCommonLookupFrequency(vtxCommonDevice(), saCmsBand, saCmsChan);
|
||||
|
||||
|
@ -243,10 +247,11 @@ static long saCmsConfigChanByGvar(displayPort_t *pDisp, const void *self)
|
|||
return 0;
|
||||
}
|
||||
|
||||
if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred)
|
||||
saSetBandAndChannel(saCmsBand - 1, saCmsChan - 1);
|
||||
if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred) {
|
||||
vtxCommonSetBandAndChannel(vtxCommonDevice(), saCmsBand, saCmsChan);
|
||||
}
|
||||
|
||||
saCmsFreqRef = vtxCommonLookupFrequency(vtxCommonDevice(), saCmsBand , saCmsChan);
|
||||
saCmsFreqRef = vtxCommonLookupFrequency(vtxCommonDevice(), saCmsBand, saCmsChan);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
@ -365,7 +370,7 @@ static long saCmsConfigOpmodelByGvar(displayPort_t *pDisp, const void *self)
|
|||
// out-range receivers from getting blinded.
|
||||
saCmsPitFMode = 0;
|
||||
saCmsConfigPitFModeByGvar(pDisp, self);
|
||||
if(saDevice.version >= 3) {
|
||||
if (saDevice.version >= 3) {
|
||||
saSetMode(SA_MODE_SET_IN_RANGE_PITMODE | ((saDevice.mode & SA_MODE_GET_PITMODE) ? 0 : SA_MODE_CLR_PITMODE));
|
||||
}
|
||||
|
||||
|
@ -421,19 +426,17 @@ static OSD_TAB_t saCmsEntPower;
|
|||
|
||||
static void saCmsInitNames(void)
|
||||
{
|
||||
vtxDevice_t *device = vtxCommonDevice();
|
||||
|
||||
saCmsEntBand.val = &saCmsBand;
|
||||
saCmsEntBand.max = device->capability.bandCount;
|
||||
saCmsEntBand.names = device->bandNames;
|
||||
saCmsEntBand.max = vtxTableBandCount;
|
||||
saCmsEntBand.names = vtxTableBandNames;
|
||||
|
||||
saCmsEntChan.val = &saCmsChan;
|
||||
saCmsEntChan.max = device->capability.channelCount;
|
||||
saCmsEntChan.names = device->channelNames;
|
||||
saCmsEntChan.max = vtxTableChannelCount;
|
||||
saCmsEntChan.names = vtxTableChannelNames;
|
||||
|
||||
saCmsEntPower.val = &saCmsPower;
|
||||
saCmsEntPower.max = device->capability.powerCount;
|
||||
saCmsEntPower.names = device->powerNames;
|
||||
saCmsEntPower.max = vtxTablePowerLevels;
|
||||
saCmsEntPower.names = vtxTablePowerLabels;
|
||||
}
|
||||
|
||||
static OSD_UINT16_t saCmsEntFreqRef = { &saCmsFreqRef, 5600, 5900, 0 };
|
||||
|
@ -462,7 +465,7 @@ static const char * const saCmsPitNames[] = {
|
|||
};
|
||||
|
||||
static OSD_TAB_t saCmsEntPitFMode = { &saCmsPitFMode, 1, saCmsPitFModeNames };
|
||||
static OSD_TAB_t saCmsEntPit = {&saCmsPit , 2, saCmsPitNames};
|
||||
static OSD_TAB_t saCmsEntPit = {&saCmsPit, 2, saCmsPitNames};
|
||||
|
||||
static long sacms_SetupTopMenu(void); // Forward
|
||||
|
||||
|
@ -520,7 +523,7 @@ static long saCmsCommence(displayPort_t *pDisp, const void *self)
|
|||
}
|
||||
}
|
||||
|
||||
if(newSettings.power == saCmsPower && saCmsPit > 0) {
|
||||
if (newSettings.power == saCmsPower && saCmsPit > 0) {
|
||||
vtxCommonSetPitMode(vtxCommonDevice(), saCmsPit == 2);
|
||||
}
|
||||
newSettings.power = saCmsPower;
|
||||
|
|
|
@ -22,6 +22,7 @@
|
|||
#include <stdint.h>
|
||||
#include <ctype.h>
|
||||
#include <string.h>
|
||||
#include <drivers/vtx_table.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
|
@ -37,7 +38,6 @@
|
|||
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "io/vtx_string.h"
|
||||
#include "io/vtx_tramp.h"
|
||||
#include "io/vtx.h"
|
||||
|
||||
|
@ -49,17 +49,22 @@ void trampCmsUpdateStatusString(void)
|
|||
{
|
||||
vtxDevice_t *vtxDevice = vtxCommonDevice();
|
||||
|
||||
#if defined(USE_VTX_TABLE)
|
||||
if (vtxDevice->capability.bandCount == 0 || vtxDevice->capability.powerCount == 0) {
|
||||
if (vtxTableBandCount == 0 || vtxTablePowerLevels == 0) {
|
||||
strncpy(trampCmsStatusString, "PLEASE CONFIGURE VTXTABLE", sizeof(trampCmsStatusString));
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
trampCmsStatusString[0] = '*';
|
||||
trampCmsStatusString[1] = ' ';
|
||||
trampCmsStatusString[2] = vtxCommonLookupBandLetter(vtxDevice, trampBand);
|
||||
trampCmsStatusString[3] = vtxCommonLookupChannelName(vtxDevice, trampChannel)[0];
|
||||
uint8_t band;
|
||||
uint8_t chan;
|
||||
if (!vtxCommonGetBandAndChannel(vtxDevice, &band, &chan) || (band == 0 && chan == 0)) {
|
||||
trampCmsStatusString[2] = 'U';//user freq
|
||||
trampCmsStatusString[3] = 'F';
|
||||
} else {
|
||||
trampCmsStatusString[2] = vtxCommonLookupBandLetter(vtxDevice, band);
|
||||
trampCmsStatusString[3] = vtxCommonLookupChannelName(vtxDevice, chan)[0];
|
||||
}
|
||||
trampCmsStatusString[4] = ' ';
|
||||
|
||||
if (trampCurFreq)
|
||||
|
@ -69,9 +74,9 @@ void trampCmsUpdateStatusString(void)
|
|||
|
||||
if (trampPower) {
|
||||
tfp_sprintf(&trampCmsStatusString[9], " %c%3d", (trampPower == trampConfiguredPower) ? ' ' : '*', trampPower);
|
||||
}
|
||||
else
|
||||
} else {
|
||||
tfp_sprintf(&trampCmsStatusString[9], " ----");
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t trampCmsPitMode = 0;
|
||||
|
@ -189,8 +194,7 @@ static bool trampCmsInitSettings(void)
|
|||
return false;
|
||||
}
|
||||
|
||||
if (trampBand > 0) trampCmsBand = trampBand;
|
||||
if (trampChannel > 0) trampCmsChan = trampChannel;
|
||||
vtxCommonGetBandAndChannel(device, &trampCmsBand, &trampCmsChan);
|
||||
|
||||
trampCmsUpdateFreqRef();
|
||||
trampCmsPitMode = trampPitMode + 1;
|
||||
|
@ -202,16 +206,16 @@ static bool trampCmsInitSettings(void)
|
|||
}
|
||||
|
||||
trampCmsEntBand.val = &trampCmsBand;
|
||||
trampCmsEntBand.max = device->capability.bandCount;
|
||||
trampCmsEntBand.names = device->bandNames;
|
||||
trampCmsEntBand.max = vtxTableBandCount;
|
||||
trampCmsEntBand.names = vtxTableBandNames;
|
||||
|
||||
trampCmsEntChan.val = &trampCmsChan;
|
||||
trampCmsEntChan.max = device->capability.channelCount;
|
||||
trampCmsEntChan.names = device->channelNames;
|
||||
trampCmsEntChan.max = vtxTableChannelCount;
|
||||
trampCmsEntChan.names = vtxTableChannelNames;
|
||||
|
||||
trampCmsEntPower.val = &trampCmsPower;
|
||||
trampCmsEntPower.max = device->capability.powerCount;
|
||||
trampCmsEntPower.names = device->powerNames;
|
||||
trampCmsEntPower.max = vtxTablePowerLevels;
|
||||
trampCmsEntPower.names = vtxTablePowerLabels;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -31,9 +31,12 @@
|
|||
|
||||
#include "common/time.h"
|
||||
#include "drivers/vtx_common.h"
|
||||
#include "drivers/vtx_table.h"
|
||||
|
||||
|
||||
static vtxDevice_t *vtxDevice = NULL;
|
||||
static uint8_t selectedBand = 0;
|
||||
static uint8_t selectedChannel = 0;
|
||||
|
||||
void vtxCommonInit(void)
|
||||
{
|
||||
|
@ -76,15 +79,22 @@ void vtxCommonProcess(vtxDevice_t *vtxDevice, timeUs_t currentTimeUs)
|
|||
// band and channel are 1 origin
|
||||
void vtxCommonSetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channel)
|
||||
{
|
||||
if (band <= vtxDevice->capability.bandCount && channel <= vtxDevice->capability.channelCount) {
|
||||
uint16_t freq = vtxCommonLookupFrequency(vtxDevice, band, channel);
|
||||
if (freq != 0) {
|
||||
selectedChannel = channel;
|
||||
selectedBand = band;
|
||||
if (vtxTableIsFactoryBand[band - 1]) {
|
||||
vtxDevice->vTable->setBandAndChannel(vtxDevice, band, channel);
|
||||
} else {
|
||||
vtxDevice->vTable->setFrequency(vtxDevice, freq);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// index is zero origin, zero = power off completely
|
||||
// index is one origin, zero = unknown power level
|
||||
void vtxCommonSetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index)
|
||||
{
|
||||
if (index <= vtxDevice->capability.powerCount) {
|
||||
if (index <= vtxTablePowerLevels) {
|
||||
vtxDevice->vTable->setPowerByIndex(vtxDevice, index);
|
||||
}
|
||||
}
|
||||
|
@ -97,12 +107,28 @@ void vtxCommonSetPitMode(vtxDevice_t *vtxDevice, uint8_t onOff)
|
|||
|
||||
void vtxCommonSetFrequency(vtxDevice_t *vtxDevice, uint16_t frequency)
|
||||
{
|
||||
selectedBand = 0;
|
||||
selectedChannel = 0;
|
||||
vtxDevice->vTable->setFrequency(vtxDevice, frequency);
|
||||
}
|
||||
|
||||
bool vtxCommonGetBandAndChannel(const vtxDevice_t *vtxDevice, uint8_t *pBand, uint8_t *pChannel)
|
||||
{
|
||||
return vtxDevice->vTable->getBandAndChannel(vtxDevice, pBand, pChannel);
|
||||
bool result = vtxDevice->vTable->getBandAndChannel(vtxDevice, pBand, pChannel);
|
||||
if ((!result || (*pBand == 0 && *pChannel == 0)) && selectedBand != 0 && selectedChannel != 0
|
||||
&& !vtxTableIsFactoryBand[selectedBand - 1]) {
|
||||
uint16_t freq;
|
||||
result = vtxCommonGetFrequency(vtxDevice, &freq);
|
||||
if (!result || freq != vtxCommonLookupFrequency(vtxDevice, selectedBand, selectedChannel)) {
|
||||
return false;
|
||||
} else {
|
||||
*pBand = selectedBand;
|
||||
*pChannel = selectedChannel;
|
||||
return true;
|
||||
}
|
||||
} else {
|
||||
return result;
|
||||
}
|
||||
}
|
||||
|
||||
bool vtxCommonGetPowerIndex(const vtxDevice_t *vtxDevice, uint8_t *pIndex)
|
||||
|
@ -120,16 +146,10 @@ bool vtxCommonGetFrequency(const vtxDevice_t *vtxDevice, uint16_t *pFrequency)
|
|||
return vtxDevice->vTable->getFrequency(vtxDevice, pFrequency);
|
||||
}
|
||||
|
||||
bool vtxCommonGetDeviceCapability(const vtxDevice_t *vtxDevice, vtxDeviceCapability_t *pDeviceCapability)
|
||||
{
|
||||
memcpy(pDeviceCapability, &vtxDevice->capability, sizeof(vtxDeviceCapability_t));
|
||||
return true;
|
||||
}
|
||||
|
||||
const char *vtxCommonLookupBandName(const vtxDevice_t *vtxDevice, int band)
|
||||
{
|
||||
if (vtxDevice) {
|
||||
return vtxDevice->bandNames[band];
|
||||
return vtxTableBandNames[band];
|
||||
} else {
|
||||
return "?";
|
||||
}
|
||||
|
@ -138,7 +158,7 @@ const char *vtxCommonLookupBandName(const vtxDevice_t *vtxDevice, int band)
|
|||
char vtxCommonLookupBandLetter(const vtxDevice_t *vtxDevice, int band)
|
||||
{
|
||||
if (vtxDevice) {
|
||||
return vtxDevice->bandLetters[band];
|
||||
return vtxTableBandLetters[band];
|
||||
} else {
|
||||
return '?';
|
||||
}
|
||||
|
@ -147,25 +167,21 @@ char vtxCommonLookupBandLetter(const vtxDevice_t *vtxDevice, int band)
|
|||
const char *vtxCommonLookupChannelName(const vtxDevice_t *vtxDevice, int channel)
|
||||
{
|
||||
if (vtxDevice) {
|
||||
return vtxDevice->channelNames[channel];
|
||||
return vtxTableChannelNames[channel];
|
||||
} else {
|
||||
return "?";
|
||||
}
|
||||
}
|
||||
|
||||
// XXX FIXME Size of a band in the frequency table is now fixed at
|
||||
// VTX_SETTINGS_MAX_CHANNEL (or VTX_TABLE_MAX_CHANNELS).
|
||||
// Size constant should be consolidated soon or later.
|
||||
|
||||
//Converts frequency (in MHz) to band and channel values.
|
||||
bool vtxCommonLookupBandChan(const vtxDevice_t *vtxDevice, uint16_t freq, uint8_t *pBand, uint8_t *pChannel)
|
||||
{
|
||||
if (vtxDevice) {
|
||||
// Use reverse lookup order so that 5880Mhz
|
||||
// get Raceband 7 instead of Fatshark 8.
|
||||
for (int band = vtxDevice->capability.bandCount - 1 ; band >= 0 ; band--) {
|
||||
for (int channel = 0 ; channel < vtxDevice->capability.channelCount ; channel++) {
|
||||
if (vtxDevice->frequencyTable[band * VTX_SETTINGS_MAX_CHANNEL + channel] == freq) {
|
||||
for (int band = vtxTableBandCount - 1 ; band >= 0 ; band--) {
|
||||
for (int channel = 0 ; channel < vtxTableChannelCount ; channel++) {
|
||||
if (vtxTableFrequency[band][channel] == freq) {
|
||||
*pBand = band + 1;
|
||||
*pChannel = channel + 1;
|
||||
return true;
|
||||
|
@ -187,9 +203,9 @@ bool vtxCommonLookupBandChan(const vtxDevice_t *vtxDevice, uint16_t freq, uint8_
|
|||
uint16_t vtxCommonLookupFrequency(const vtxDevice_t *vtxDevice, int band, int channel)
|
||||
{
|
||||
if (vtxDevice) {
|
||||
if (band > 0 && band <= vtxDevice->capability.bandCount &&
|
||||
channel > 0 && channel <= vtxDevice->capability.channelCount) {
|
||||
return vtxDevice->frequencyTable[(band - 1) * VTX_SETTINGS_MAX_CHANNEL + (channel - 1)];
|
||||
if (band > 0 && band <= vtxTableBandCount &&
|
||||
channel > 0 && channel <= vtxTableChannelCount) {
|
||||
return vtxTableFrequency[band - 1][channel - 1];
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -199,18 +215,19 @@ uint16_t vtxCommonLookupFrequency(const vtxDevice_t *vtxDevice, int band, int ch
|
|||
const char *vtxCommonLookupPowerName(const vtxDevice_t *vtxDevice, int index)
|
||||
{
|
||||
if (vtxDevice) {
|
||||
return vtxDevice->powerNames[index];
|
||||
return vtxTablePowerLabels[index];
|
||||
} else {
|
||||
return "?";
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t vtxCommonLookupPowerValue(const vtxDevice_t *vtxDevice, int index)
|
||||
bool vtxCommonLookupPowerValue(const vtxDevice_t *vtxDevice, int index, uint16_t *pPowerValue)
|
||||
{
|
||||
if (vtxDevice && index > 0) {
|
||||
return vtxDevice->powerValues[index - 1];
|
||||
if (vtxDevice && index > 0 && index <= vtxTablePowerLevels) {
|
||||
*pPowerValue = vtxTablePowerValues[index - 1];
|
||||
return true;
|
||||
} else {
|
||||
return 0;
|
||||
return false;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -27,20 +27,6 @@
|
|||
#include "platform.h"
|
||||
#include "common/time.h"
|
||||
|
||||
#define VTX_SETTINGS_NO_BAND 0 // used for custom frequency selection mode
|
||||
#define VTX_SETTINGS_MIN_BAND 1
|
||||
#define VTX_SETTINGS_MAX_BAND 5
|
||||
#define VTX_SETTINGS_MIN_CHANNEL 1
|
||||
#define VTX_SETTINGS_MAX_CHANNEL 8
|
||||
|
||||
#define VTX_SETTINGS_BAND_COUNT (VTX_SETTINGS_MAX_BAND - VTX_SETTINGS_MIN_BAND + 1)
|
||||
#define VTX_SETTINGS_CHANNEL_COUNT (VTX_SETTINGS_MAX_CHANNEL - VTX_SETTINGS_MIN_CHANNEL + 1)
|
||||
|
||||
#define VTX_SETTINGS_DEFAULT_BAND 4
|
||||
#define VTX_SETTINGS_DEFAULT_CHANNEL 1
|
||||
#define VTX_SETTINGS_DEFAULT_FREQ 5740
|
||||
#define VTX_SETTINGS_DEFAULT_PITMODE_FREQ 0
|
||||
|
||||
#define VTX_SETTINGS_MAX_FREQUENCY_MHZ 5999 //max freq (in MHz) for 'vtx_freq' setting
|
||||
|
||||
#if defined(USE_VTX_RTC6705)
|
||||
|
@ -51,19 +37,8 @@
|
|||
|
||||
#if defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP)
|
||||
|
||||
#define VTX_SETTINGS_POWER_COUNT 5
|
||||
#define VTX_SETTINGS_DEFAULT_POWER 1
|
||||
#define VTX_SETTINGS_MIN_POWER 0
|
||||
#define VTX_SETTINGS_MIN_USER_FREQ 5000
|
||||
#define VTX_SETTINGS_MAX_USER_FREQ 5999
|
||||
#define VTX_SETTINGS_FREQCMD
|
||||
|
||||
#elif defined(USE_VTX_RTC6705)
|
||||
|
||||
#define VTX_SETTINGS_POWER_COUNT VTX_RTC6705_POWER_COUNT
|
||||
#define VTX_SETTINGS_DEFAULT_POWER VTX_RTC6705_DEFAULT_POWER
|
||||
#define VTX_SETTINGS_MIN_POWER VTX_RTC6705_MIN_POWER
|
||||
|
||||
#endif
|
||||
|
||||
// check value for MSP_SET_VTX_CONFIG to determine if value is encoded
|
||||
|
@ -79,7 +54,7 @@ typedef enum {
|
|||
VTXDEV_UNKNOWN = 0xFF,
|
||||
} vtxDevType_e;
|
||||
|
||||
// VTX magic numbers
|
||||
// VTX magic numbers used for spektrum vtx control
|
||||
#define VTX_COMMON_BAND_USER 0
|
||||
#define VTX_COMMON_BAND_A 1
|
||||
#define VTX_COMMON_BAND_B 2
|
||||
|
@ -88,51 +63,28 @@ typedef enum {
|
|||
#define VTX_COMMON_BAND_RACE 5
|
||||
|
||||
// RTC6705 RF Power index "---", 25 or 200 mW
|
||||
#define VTX_6705_POWER_OFF 0
|
||||
#define VTX_6705_POWER_25 1
|
||||
#define VTX_6705_POWER_200 2
|
||||
#define VTX_6705_POWER_OFF 1
|
||||
#define VTX_6705_POWER_25 2
|
||||
#define VTX_6705_POWER_200 3
|
||||
|
||||
// SmartAudio "---", 25, 200, 500, 800 mW
|
||||
#define VTX_SA_POWER_OFF 0
|
||||
#define VTX_SA_POWER_OFF 1 //1 goes to min power whereas 0 doesnt do anything (illegal index).
|
||||
#define VTX_SA_POWER_25 1
|
||||
#define VTX_SA_POWER_200 2
|
||||
#define VTX_SA_POWER_500 3
|
||||
#define VTX_SA_POWER_800 4
|
||||
|
||||
// Tramp "---", 25, 100, 200, 400, 600 mW
|
||||
#define VTX_TRAMP_POWER_OFF 0
|
||||
#define VTX_TRAMP_POWER_OFF 1 //same as with SmartAudio
|
||||
#define VTX_TRAMP_POWER_25 1
|
||||
#define VTX_TRAMP_POWER_100 2
|
||||
#define VTX_TRAMP_POWER_200 3
|
||||
#define VTX_TRAMP_POWER_400 4
|
||||
#define VTX_TRAMP_POWER_600 5
|
||||
|
||||
|
||||
typedef struct vtxDeviceCapability_s {
|
||||
uint8_t bandCount;
|
||||
uint8_t channelCount;
|
||||
uint8_t powerCount;
|
||||
uint8_t filler;
|
||||
} vtxDeviceCapability_t;
|
||||
|
||||
struct vtxVTable_s;
|
||||
typedef struct vtxDevice_s {
|
||||
const struct vtxVTable_s * const vTable;
|
||||
|
||||
vtxDeviceCapability_t capability;
|
||||
|
||||
const uint16_t *frequencyTable; // Array of [bandCount][channelCount]
|
||||
const char **bandNames; // char *bandNames[bandCount + 1]
|
||||
const char **channelNames; // char *channelNames[channelCount + 1]
|
||||
const char *bandLetters; // char bandLetters[bandCount + 1]
|
||||
const uint16_t *powerValues; // uint16 powerValues[powerCount]
|
||||
const char **powerNames; // char *powerNames[powerCount + 1]
|
||||
|
||||
uint16_t frequency;
|
||||
uint8_t band; // Band = 1, 1-based
|
||||
uint8_t channel; // CH1 = 1, 1-based
|
||||
uint8_t powerIndex; // Lowest/Off = 0
|
||||
uint8_t pitMode; // 0 = non-PIT, 1 = PIT
|
||||
const struct vtxVTable_s *const vTable;
|
||||
} vtxDevice_t;
|
||||
|
||||
|
||||
|
@ -177,7 +129,6 @@ bool vtxCommonGetBandAndChannel(const vtxDevice_t *vtxDevice, uint8_t *pBand, ui
|
|||
bool vtxCommonGetPowerIndex(const vtxDevice_t *vtxDevice, uint8_t *pIndex);
|
||||
bool vtxCommonGetPitMode(const vtxDevice_t *vtxDevice, uint8_t *pOnOff);
|
||||
bool vtxCommonGetFrequency(const vtxDevice_t *vtxDevice, uint16_t *pFreq);
|
||||
bool vtxCommonGetDeviceCapability(const vtxDevice_t *vtxDevice, vtxDeviceCapability_t *pDeviceCapability);
|
||||
const char *vtxCommonLookupBandName(const vtxDevice_t *vtxDevice, int band);
|
||||
char vtxCommonLookupBandLetter(const vtxDevice_t *vtxDevice, int band);
|
||||
char vtxCommonGetBandLetter(const vtxDevice_t *vtxDevice, int band);
|
||||
|
@ -185,4 +136,4 @@ const char *vtxCommonLookupChannelName(const vtxDevice_t *vtxDevice, int channel
|
|||
uint16_t vtxCommonLookupFrequency(const vtxDevice_t *vtxDevice, int band, int channel);
|
||||
bool vtxCommonLookupBandChan(const vtxDevice_t *vtxDevice, uint16_t freq, uint8_t *pBand, uint8_t *pChannel);
|
||||
const char *vtxCommonLookupPowerName(const vtxDevice_t *vtxDevice, int index);
|
||||
uint16_t vtxCommonLookupPowerValue(const vtxDevice_t *vtxDevice, int index);
|
||||
bool vtxCommonLookupPowerValue(const vtxDevice_t *vtxDevice, int index, uint16_t *pPowerValue);
|
||||
|
|
|
@ -178,7 +178,7 @@ void rtc6705SetFrequency(uint16_t frequency)
|
|||
|
||||
void rtc6705SetRFPower(uint8_t rf_power)
|
||||
{
|
||||
rf_power = constrain(rf_power, VTX_RTC6705_MIN_POWER, VTX_RTC6705_POWER_COUNT - 1);
|
||||
rf_power = constrain(rf_power, VTX_RTC6705_MIN_POWER_VALUE, VTX_RTC6705_POWER_COUNT - 1);
|
||||
|
||||
spiSetDivisor(busdev->busdev_u.spi.instance, SPI_CLOCK_SLOW);
|
||||
|
||||
|
|
|
@ -31,15 +31,13 @@
|
|||
|
||||
#include "pg/vtx_io.h"
|
||||
|
||||
#define VTX_RTC6705_BAND_COUNT 5
|
||||
#define VTX_RTC6705_CHANNEL_COUNT 8
|
||||
#define VTX_RTC6705_POWER_COUNT 3
|
||||
#define VTX_RTC6705_DEFAULT_POWER 1
|
||||
#define VTX_RTC6705_DEFAULT_POWER_INDEX 2
|
||||
|
||||
#if defined(RTC6705_POWER_PIN)
|
||||
#define VTX_RTC6705_MIN_POWER 0
|
||||
#define VTX_RTC6705_MIN_POWER_VALUE 0
|
||||
#else
|
||||
#define VTX_RTC6705_MIN_POWER 1
|
||||
#define VTX_RTC6705_MIN_POWER_VALUE 1
|
||||
#endif
|
||||
|
||||
#define VTX_RTC6705_FREQ_MIN 5600
|
||||
|
|
|
@ -27,27 +27,61 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(USE_VTX_TABLE)
|
||||
#include "drivers/vtx_table.h"
|
||||
|
||||
#if defined(USE_VTX_TABLE)
|
||||
#include "common/printf.h"
|
||||
|
||||
#include "pg/vtx_table.h"
|
||||
#include "drivers/vtx_common.h"
|
||||
#include "drivers/vtx_table.h"
|
||||
#endif
|
||||
|
||||
|
||||
#if defined(USE_VTX_TABLE)
|
||||
int vtxTableBandCount;
|
||||
int vtxTableChannelCount;
|
||||
uint16_t vtxTableFrequency[VTX_TABLE_MAX_BANDS][VTX_TABLE_MAX_CHANNELS];
|
||||
const char * vtxTableBandNames[VTX_TABLE_MAX_BANDS + 1];
|
||||
char vtxTableBandLetters[VTX_TABLE_MAX_BANDS + 1];
|
||||
const char * vtxTableChannelNames[VTX_TABLE_MAX_CHANNELS + 1];
|
||||
bool vtxTableIsFactoryBand[VTX_TABLE_MAX_BANDS];
|
||||
|
||||
int vtxTablePowerLevels;
|
||||
uint16_t vtxTablePowerValues[VTX_TABLE_MAX_POWER_LEVELS];
|
||||
const char * vtxTablePowerLabels[VTX_TABLE_MAX_POWER_LEVELS + 1];
|
||||
|
||||
#else
|
||||
|
||||
int vtxTableBandCount = VTX_TABLE_MAX_BANDS;
|
||||
int vtxTableChannelCount = VTX_TABLE_MAX_CHANNELS;
|
||||
uint16_t vtxTableFrequency[VTX_TABLE_MAX_BANDS][VTX_TABLE_MAX_CHANNELS] = {
|
||||
{ 5865, 5845, 5825, 5805, 5785, 5765, 5745, 5725 }, // Boscam A
|
||||
{ 5733, 5752, 5771, 5790, 5809, 5828, 5847, 5866 }, // Boscam B
|
||||
{ 5705, 5685, 5665, 5645, 5885, 5905, 5925, 5945 }, // Boscam E
|
||||
{ 5740, 5760, 5780, 5800, 5820, 5840, 5860, 5880 }, // FatShark
|
||||
{ 5658, 5695, 5732, 5769, 5806, 5843, 5880, 5917 }, // RaceBand
|
||||
};
|
||||
const char * vtxTableBandNames[VTX_TABLE_MAX_BANDS + 1] = {
|
||||
"--------",
|
||||
"BOSCAM A",
|
||||
"BOSCAM B",
|
||||
"BOSCAM E",
|
||||
"FATSHARK",
|
||||
"RACEBAND",
|
||||
};
|
||||
char vtxTableBandLetters[VTX_TABLE_MAX_BANDS + 1] = "-ABEFR";
|
||||
const char * vtxTableChannelNames[VTX_TABLE_MAX_CHANNELS + 1] = {
|
||||
"-", "1", "2", "3", "4", "5", "6", "7", "8",
|
||||
};
|
||||
bool vtxTableIsFactoryBand[VTX_TABLE_MAX_BANDS];
|
||||
int vtxTablePowerLevels;
|
||||
uint16_t vtxTablePowerValues[VTX_TABLE_MAX_POWER_LEVELS];
|
||||
const char * vtxTablePowerLabels[VTX_TABLE_MAX_POWER_LEVELS + 1];
|
||||
#endif
|
||||
|
||||
void vtxTableInit(void)
|
||||
{
|
||||
#if defined(USE_VTX_TABLE)
|
||||
const vtxTableConfig_t *config = vtxTableConfig();
|
||||
|
||||
vtxTableBandCount = config->bands;
|
||||
|
@ -59,6 +93,7 @@ void vtxTableInit(void)
|
|||
}
|
||||
vtxTableBandNames[band + 1] = config->bandNames[band];
|
||||
vtxTableBandLetters[band + 1] = config->bandLetters[band];
|
||||
vtxTableIsFactoryBand[band] = config->isFactoryBand[band];
|
||||
}
|
||||
|
||||
vtxTableBandNames[0] = "--------";
|
||||
|
@ -76,8 +111,30 @@ void vtxTableInit(void)
|
|||
vtxTablePowerLabels[0] = "---";
|
||||
|
||||
vtxTablePowerLevels = config->powerLevels;
|
||||
#else
|
||||
for (int band = 0; band < VTX_TABLE_MAX_BANDS; band++) {
|
||||
vtxTableIsFactoryBand[band] = true;
|
||||
}
|
||||
for (int powerIndex = 0; powerIndex < VTX_TABLE_MAX_POWER_LEVELS; powerIndex++) {
|
||||
vtxTablePowerValues[powerIndex] = 0;
|
||||
vtxTablePowerLabels[powerIndex] = NULL;
|
||||
}
|
||||
vtxTablePowerLevels = VTX_TABLE_MAX_POWER_LEVELS;
|
||||
vtxTableSetFactoryBands(false);
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifndef USE_VTX_TABLE
|
||||
void vtxTableSetFactoryBands(bool isFactory)
|
||||
{
|
||||
for(int i = 0;i < VTX_TABLE_MAX_BANDS; i++) {
|
||||
vtxTableIsFactoryBand[i] = isFactory;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(USE_VTX_TABLE)
|
||||
|
||||
void vtxTableStrncpyWithPad(char *dst, const char *src, int length)
|
||||
{
|
||||
char c;
|
||||
|
@ -118,6 +175,7 @@ void vtxTableConfigClearBand(vtxTableConfig_t *config, int band)
|
|||
tfp_sprintf(tempbuf, "BAND%d", band + 1);
|
||||
vtxTableStrncpyWithPad(config->bandNames[band], tempbuf, VTX_TABLE_BAND_NAME_LENGTH);
|
||||
config->bandLetters[band] = '1' + band;
|
||||
config->isFactoryBand[band] = false;
|
||||
}
|
||||
|
||||
void vtxTableConfigClearPowerValues(vtxTableConfig_t *config, int start)
|
||||
|
|
|
@ -26,12 +26,34 @@
|
|||
|
||||
#include "drivers/vtx_common.h"
|
||||
|
||||
#ifdef USE_VTX_TABLE
|
||||
#define VTX_TABLE_MAX_BANDS 8 // Maximum number of bands
|
||||
#define VTX_TABLE_MAX_CHANNELS 8 // Maximum number of channels per band
|
||||
#define VTX_TABLE_MAX_POWER_LEVELS 8 // Maximum number of power levels
|
||||
#define VTX_TABLE_CHANNEL_NAME_LENGTH 1
|
||||
#define VTX_TABLE_BAND_NAME_LENGTH 8
|
||||
#define VTX_TABLE_POWER_LABEL_LENGTH 3
|
||||
#else
|
||||
#define VTX_TABLE_MAX_BANDS 5 // default freq table has 5 bands
|
||||
#define VTX_TABLE_MAX_CHANNELS 8 // and eight channels
|
||||
#define VTX_TABLE_MAX_POWER_LEVELS 5 //max of VTX_TRAMP_POWER_COUNT, VTX_SMARTAUDIO_POWER_COUNT and VTX_RTC6705_POWER_COUNT
|
||||
#define VTX_TABLE_CHANNEL_NAME_LENGTH 1
|
||||
#define VTX_TABLE_BAND_NAME_LENGTH 8
|
||||
#define VTX_TABLE_POWER_LABEL_LENGTH 3
|
||||
#endif
|
||||
|
||||
|
||||
#define VTX_TABLE_MIN_USER_FREQ 5000
|
||||
#define VTX_TABLE_MAX_USER_FREQ 5999
|
||||
#define VTX_TABLE_DEFAULT_BAND 4
|
||||
#define VTX_TABLE_DEFAULT_CHANNEL 1
|
||||
#define VTX_TABLE_DEFAULT_FREQ 5740
|
||||
#define VTX_TABLE_DEFAULT_PITMODE_FREQ 0
|
||||
#ifdef USE_VTX_RTC6705
|
||||
#define VTX_TABLE_DEFAULT_POWER VTX_RTC6705_DEFAULT_POWER_INDEX
|
||||
#else
|
||||
#define VTX_TABLE_DEFAULT_POWER 1 //lowest actual power mode
|
||||
#endif
|
||||
|
||||
struct vtxTableConfig_s;
|
||||
void vtxTableInit(void);
|
||||
|
@ -40,13 +62,17 @@ void vtxTableConfigClearBand(struct vtxTableConfig_s *config, int band);
|
|||
void vtxTableConfigClearPowerValues(struct vtxTableConfig_s *config, int start);
|
||||
void vtxTableConfigClearPowerLabels(struct vtxTableConfig_s *config, int start);
|
||||
void vtxTableConfigClearChannels(struct vtxTableConfig_s *config, int band, int channels);
|
||||
#ifndef USE_VTX_TABLE
|
||||
void vtxTableSetFactoryBands(bool isFactory);
|
||||
#endif
|
||||
|
||||
extern int vtxTableBandCount;
|
||||
extern int vtxTableChannelCount;
|
||||
extern uint16_t vtxTableFrequency[VTX_TABLE_MAX_BANDS][VTX_TABLE_MAX_CHANNELS];
|
||||
extern const char * vtxTableBandNames[VTX_TABLE_MAX_BANDS + 1];
|
||||
extern const char *vtxTableBandNames[VTX_TABLE_MAX_BANDS + 1];
|
||||
extern char vtxTableBandLetters[VTX_TABLE_MAX_BANDS + 1];
|
||||
extern const char * vtxTableChannelNames[VTX_TABLE_MAX_CHANNELS + 1];
|
||||
extern const char *vtxTableChannelNames[VTX_TABLE_MAX_CHANNELS + 1];
|
||||
extern bool vtxTableIsFactoryBand[VTX_TABLE_MAX_BANDS];
|
||||
extern int vtxTablePowerLevels;
|
||||
extern uint16_t vtxTablePowerValues[VTX_TABLE_MAX_POWER_LEVELS];
|
||||
extern const char * vtxTablePowerLabels[VTX_TABLE_MAX_POWER_LEVELS + 1];
|
||||
extern const char *vtxTablePowerLabels[VTX_TABLE_MAX_POWER_LEVELS + 1];
|
||||
|
|
|
@ -867,7 +867,7 @@ void init(void)
|
|||
baroSetCalibrationCycles(CALIBRATING_BARO_CYCLES);
|
||||
#endif
|
||||
|
||||
#ifdef USE_VTX_TABLE
|
||||
#if defined(USE_VTX_COMMON) || defined(USE_VTX_CONTROL)
|
||||
vtxTableInit();
|
||||
#endif
|
||||
|
||||
|
|
|
@ -65,7 +65,6 @@
|
|||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/vtx_string.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
|
|
|
@ -26,7 +26,6 @@
|
|||
#include "fc/config.h"
|
||||
#include "drivers/vtx_common.h"
|
||||
#include "io/vtx.h"
|
||||
#include "io/vtx_string.h"
|
||||
|
||||
#include "io/spektrum_vtx_control.h"
|
||||
|
||||
|
|
|
@ -31,6 +31,7 @@
|
|||
#include "common/time.h"
|
||||
|
||||
#include "drivers/vtx_common.h"
|
||||
#include "drivers/vtx_table.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_modes.h"
|
||||
|
@ -38,7 +39,6 @@
|
|||
|
||||
#include "flight/failsafe.h"
|
||||
|
||||
#include "io/vtx_string.h"
|
||||
#include "io/vtx_control.h"
|
||||
|
||||
#include "pg/pg.h"
|
||||
|
@ -50,13 +50,13 @@
|
|||
PG_REGISTER_WITH_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig, PG_VTX_SETTINGS_CONFIG, 0);
|
||||
|
||||
PG_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig,
|
||||
.band = VTX_SETTINGS_DEFAULT_BAND,
|
||||
.channel = VTX_SETTINGS_DEFAULT_CHANNEL,
|
||||
.power = VTX_SETTINGS_DEFAULT_POWER,
|
||||
.freq = VTX_SETTINGS_DEFAULT_FREQ,
|
||||
.pitModeFreq = VTX_SETTINGS_DEFAULT_PITMODE_FREQ,
|
||||
.band = VTX_TABLE_DEFAULT_BAND,
|
||||
.channel = VTX_TABLE_DEFAULT_CHANNEL,
|
||||
.power = VTX_TABLE_DEFAULT_POWER,
|
||||
.freq = VTX_TABLE_DEFAULT_FREQ,
|
||||
.pitModeFreq = VTX_TABLE_DEFAULT_PITMODE_FREQ,
|
||||
.lowPowerDisarm = VTX_LOW_POWER_DISARM_OFF,
|
||||
);
|
||||
);
|
||||
|
||||
typedef enum {
|
||||
VTX_PARAM_POWER = 0,
|
||||
|
@ -88,7 +88,7 @@ void vtxInit(void)
|
|||
#if defined(VTX_SETTINGS_FREQCMD)
|
||||
// constrain pit mode frequency
|
||||
if (vtxSettingsConfig()->pitModeFreq) {
|
||||
const uint16_t constrainedPitModeFreq = MAX(vtxSettingsConfig()->pitModeFreq, VTX_SETTINGS_MIN_USER_FREQ);
|
||||
const uint16_t constrainedPitModeFreq = MAX(vtxSettingsConfig()->pitModeFreq, VTX_TABLE_MIN_USER_FREQ);
|
||||
if (constrainedPitModeFreq != vtxSettingsConfig()->pitModeFreq) {
|
||||
vtxSettingsConfigMutable()->pitModeFreq = constrainedPitModeFreq;
|
||||
settingsUpdated = true;
|
||||
|
@ -116,14 +116,14 @@ STATIC_UNIT_TESTED vtxSettingsConfig_t vtxGetSettings(void)
|
|||
if (IS_RC_MODE_ACTIVE(BOXVTXPITMODE) && settings.pitModeFreq) {
|
||||
settings.band = 0;
|
||||
settings.freq = settings.pitModeFreq;
|
||||
settings.power = VTX_SETTINGS_DEFAULT_POWER;
|
||||
settings.power = VTX_TABLE_DEFAULT_POWER;
|
||||
}
|
||||
#endif
|
||||
|
||||
if (!ARMING_FLAG(ARMED) && !failsafeIsActive() &&
|
||||
(settings.lowPowerDisarm == VTX_LOW_POWER_DISARM_ALWAYS ||
|
||||
(settings.lowPowerDisarm == VTX_LOW_POWER_DISARM_UNTIL_FIRST_ARM && !ARMING_FLAG(WAS_EVER_ARMED)))) {
|
||||
settings.power = VTX_SETTINGS_DEFAULT_POWER;
|
||||
settings.power = VTX_TABLE_DEFAULT_POWER;
|
||||
}
|
||||
|
||||
return settings;
|
||||
|
@ -131,7 +131,7 @@ STATIC_UNIT_TESTED vtxSettingsConfig_t vtxGetSettings(void)
|
|||
|
||||
static bool vtxProcessBandAndChannel(vtxDevice_t *vtxDevice)
|
||||
{
|
||||
if(!ARMING_FLAG(ARMED)) {
|
||||
if (!ARMING_FLAG(ARMED)) {
|
||||
uint8_t vtxBand;
|
||||
uint8_t vtxChan;
|
||||
if (vtxCommonGetBandAndChannel(vtxDevice, &vtxBand, &vtxChan)) {
|
||||
|
@ -148,7 +148,7 @@ static bool vtxProcessBandAndChannel(vtxDevice_t *vtxDevice)
|
|||
#if defined(VTX_SETTINGS_FREQCMD)
|
||||
static bool vtxProcessFrequency(vtxDevice_t *vtxDevice)
|
||||
{
|
||||
if(!ARMING_FLAG(ARMED)) {
|
||||
if (!ARMING_FLAG(ARMED)) {
|
||||
uint16_t vtxFreq;
|
||||
if (vtxCommonGetFrequency(vtxDevice, &vtxFreq)) {
|
||||
const vtxSettingsConfig_t settings = vtxGetSettings();
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <drivers/vtx_table.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
|
@ -142,25 +143,24 @@ void vtxCycleBandOrChannel(const uint8_t bandStep, const uint8_t channelStep)
|
|||
const vtxDevice_t *vtxDevice = vtxCommonDevice();
|
||||
if (vtxDevice) {
|
||||
uint8_t band = 0, channel = 0;
|
||||
vtxDeviceCapability_t capability;
|
||||
|
||||
const bool haveAllNeededInfo = vtxCommonGetBandAndChannel(vtxDevice, &band, &channel) && vtxCommonGetDeviceCapability(vtxDevice, &capability);
|
||||
const bool haveAllNeededInfo = vtxCommonGetBandAndChannel(vtxDevice, &band, &channel);
|
||||
if (!haveAllNeededInfo) {
|
||||
return;
|
||||
}
|
||||
|
||||
int newChannel = channel + channelStep;
|
||||
if (newChannel > capability.channelCount) {
|
||||
if (newChannel > vtxTableChannelCount) {
|
||||
newChannel = 1;
|
||||
} else if (newChannel < 1) {
|
||||
newChannel = capability.channelCount;
|
||||
newChannel = vtxTableChannelCount;
|
||||
}
|
||||
|
||||
int newBand = band + bandStep;
|
||||
if (newBand > capability.bandCount) {
|
||||
if (newBand > vtxTableBandCount) {
|
||||
newBand = 1;
|
||||
} else if (newBand < 1) {
|
||||
newBand = capability.bandCount;
|
||||
newBand = vtxTableBandCount;
|
||||
}
|
||||
|
||||
vtxSettingsConfigMutable()->band = newBand;
|
||||
|
@ -173,17 +173,16 @@ void vtxCyclePower(const uint8_t powerStep)
|
|||
const vtxDevice_t *vtxDevice = vtxCommonDevice();
|
||||
if (vtxDevice) {
|
||||
uint8_t power = 0;
|
||||
vtxDeviceCapability_t capability;
|
||||
const bool haveAllNeededInfo = vtxCommonGetPowerIndex(vtxDevice, &power) && vtxCommonGetDeviceCapability(vtxDevice, &capability);
|
||||
const bool haveAllNeededInfo = vtxCommonGetPowerIndex(vtxDevice, &power);
|
||||
if (!haveAllNeededInfo) {
|
||||
return;
|
||||
}
|
||||
|
||||
int newPower = power + powerStep;
|
||||
if (newPower >= capability.powerCount) {
|
||||
if (newPower >= vtxTablePowerLevels) {
|
||||
newPower = 0;
|
||||
} else if (newPower < 0) {
|
||||
newPower = capability.powerCount;
|
||||
newPower = vtxTablePowerLevels;
|
||||
}
|
||||
|
||||
vtxSettingsConfigMutable()->power = newPower;
|
||||
|
|
|
@ -34,16 +34,16 @@
|
|||
|
||||
#include "drivers/max7456.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/vtx_table.h"
|
||||
#include "drivers/vtx_rtc6705.h"
|
||||
|
||||
#include "io/vtx.h"
|
||||
#include "io/vtx_rtc6705.h"
|
||||
#include "io/vtx_string.h"
|
||||
|
||||
|
||||
#if defined(USE_CMS) || defined(USE_VTX_COMMON)
|
||||
const char * rtc6705PowerNames[] = {
|
||||
"OFF", "MIN", "MAX"
|
||||
#if (defined(USE_CMS) || defined(USE_VTX_COMMON)) && !defined(USE_VTX_TABLE)
|
||||
const char *rtc6705PowerNames[VTX_RTC6705_POWER_COUNT + 1] = {
|
||||
"---", "OFF", "MIN", "MAX"
|
||||
};
|
||||
#endif
|
||||
|
||||
|
@ -54,21 +54,26 @@ static vtxDevice_t vtxRTC6705 = {
|
|||
};
|
||||
#endif
|
||||
|
||||
static uint16_t rtc6705Frequency;
|
||||
static int8_t rtc6705PowerIndex;
|
||||
|
||||
static void vtxRTC6705SetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channel);
|
||||
static void vtxRTC6705SetFrequency(vtxDevice_t *vtxDevice, uint16_t frequency);
|
||||
|
||||
bool vtxRTC6705Init(void)
|
||||
{
|
||||
vtxRTC6705.capability.bandCount = VTX_SETTINGS_BAND_COUNT,
|
||||
vtxRTC6705.capability.channelCount = VTX_SETTINGS_CHANNEL_COUNT,
|
||||
vtxRTC6705.capability.powerCount = VTX_RTC6705_POWER_COUNT,
|
||||
vtxRTC6705.frequencyTable = vtxStringFrequencyTable();
|
||||
vtxRTC6705.bandNames = vtxStringBandNames();
|
||||
vtxRTC6705.bandLetters = vtxStringBandLetters();
|
||||
vtxRTC6705.channelNames = vtxStringChannelNames();
|
||||
vtxRTC6705.powerNames = rtc6705PowerNames,
|
||||
|
||||
vtxCommonSetDevice(&vtxRTC6705);
|
||||
#ifndef USE_VTX_TABLE
|
||||
//without USE_VTX_TABLE, fill vtxTable variables with default settings (instead of loading them from PG)
|
||||
vtxTablePowerLevels = VTX_RTC6705_POWER_COUNT;
|
||||
for (int i = 0; i < VTX_RTC6705_POWER_COUNT + 1; i++) {
|
||||
vtxTablePowerLabels[i] = rtc6705PowerNames[i];
|
||||
}
|
||||
for (int i = 0; i < VTX_RTC6705_POWER_COUNT; i++) {
|
||||
vtxTablePowerValues[i] = i;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
vtxInit();
|
||||
|
||||
|
@ -88,8 +93,10 @@ bool vtxRTC6705CanUpdate(void)
|
|||
#ifdef RTC6705_POWER_PIN
|
||||
static void vtxRTC6705Configure(vtxDevice_t *vtxDevice)
|
||||
{
|
||||
rtc6705SetRFPower(vtxDevice->powerIndex);
|
||||
vtxRTC6705SetBandAndChannel(vtxDevice, vtxDevice->band, vtxDevice->channel);
|
||||
uint16_t newPowerValue = 0;
|
||||
vtxCommonLookupPowerValue(vtxDevice, rtc6705PowerIndex, &newPowerValue);
|
||||
rtc6705SetRFPower(newPowerValue);
|
||||
vtxRTC6705SetFrequency(vtxDevice, rtc6705Frequency);
|
||||
}
|
||||
|
||||
static void vtxRTC6705EnableAndConfigure(vtxDevice_t *vtxDevice)
|
||||
|
@ -126,27 +133,28 @@ static bool vtxRTC6705IsReady(const vtxDevice_t *vtxDevice)
|
|||
|
||||
static void vtxRTC6705SetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channel)
|
||||
{
|
||||
while (!vtxRTC6705CanUpdate());
|
||||
|
||||
if (band >= 1 && band <= VTX_SETTINGS_BAND_COUNT && channel >= 1 && channel <= VTX_SETTINGS_CHANNEL_COUNT) {
|
||||
if (vtxDevice->powerIndex > 0) {
|
||||
vtxDevice->band = band;
|
||||
vtxDevice->channel = channel;
|
||||
vtxRTC6705SetFrequency(vtxDevice, vtxCommonLookupFrequency(vtxDevice, band, channel));
|
||||
}
|
||||
}
|
||||
UNUSED(vtxDevice);
|
||||
UNUSED(band);
|
||||
UNUSED(channel);
|
||||
//rtc6705 does not support bands and channels, only frequencies
|
||||
}
|
||||
|
||||
static void vtxRTC6705SetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index)
|
||||
{
|
||||
while (!vtxRTC6705CanUpdate());
|
||||
|
||||
uint16_t newPowerValue = 0;
|
||||
if (!vtxCommonLookupPowerValue(vtxDevice, index, &newPowerValue)) {
|
||||
return;
|
||||
}
|
||||
uint16_t currentPowerValue = 0;
|
||||
vtxCommonLookupPowerValue(vtxDevice, rtc6705PowerIndex, ¤tPowerValue);
|
||||
#ifdef RTC6705_POWER_PIN
|
||||
if (index == 0) {
|
||||
if (newPowerValue == 0) {
|
||||
// power device off
|
||||
if (vtxDevice->powerIndex > 0) {
|
||||
if (currentPowerValue > 0) {
|
||||
// on, power it off
|
||||
vtxDevice->powerIndex = index;
|
||||
rtc6705PowerIndex = index;
|
||||
rtc6705Disable();
|
||||
return;
|
||||
} else {
|
||||
|
@ -154,20 +162,20 @@ static void vtxRTC6705SetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index)
|
|||
}
|
||||
} else {
|
||||
// change rf power and maybe turn the device on first
|
||||
if (vtxDevice->powerIndex == 0) {
|
||||
if (currentPowerValue == 0) {
|
||||
// if it's powered down, power it up, wait and configure channel, band and power.
|
||||
vtxDevice->powerIndex = index;
|
||||
rtc6705PowerIndex = index;
|
||||
vtxRTC6705EnableAndConfigure(vtxDevice);
|
||||
return;
|
||||
} else {
|
||||
// if it's powered up, just set the rf power
|
||||
vtxDevice->powerIndex = index;
|
||||
rtc6705SetRFPower(index);
|
||||
rtc6705PowerIndex = index;
|
||||
rtc6705SetRFPower(newPowerValue);
|
||||
}
|
||||
}
|
||||
#else
|
||||
vtxDevice->powerIndex = MAX(index, VTX_RTC6705_MIN_POWER);
|
||||
rtc6705SetRFPower(index);
|
||||
rtc6705PowerIndex = index;
|
||||
rtc6705SetRFPower(MAX(newPowerValue, VTX_RTC6705_MIN_POWER_VALUE);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -179,23 +187,28 @@ static void vtxRTC6705SetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff)
|
|||
|
||||
static void vtxRTC6705SetFrequency(vtxDevice_t *vtxDevice, uint16_t frequency)
|
||||
{
|
||||
UNUSED(vtxDevice);
|
||||
if (frequency >= VTX_RTC6705_FREQ_MIN && frequency <= VTX_RTC6705_FREQ_MAX) {
|
||||
frequency = constrain(frequency, VTX_RTC6705_FREQ_MIN, VTX_RTC6705_FREQ_MAX);
|
||||
vtxDevice->frequency = frequency;
|
||||
rtc6705Frequency = frequency;
|
||||
rtc6705SetFrequency(frequency);
|
||||
}
|
||||
}
|
||||
|
||||
static bool vtxRTC6705GetBandAndChannel(const vtxDevice_t *vtxDevice, uint8_t *pBand, uint8_t *pChannel)
|
||||
{
|
||||
*pBand = vtxDevice->band;
|
||||
*pChannel = vtxDevice->channel;
|
||||
UNUSED(vtxDevice);
|
||||
*pBand = 0;
|
||||
*pChannel = 0;
|
||||
//rtc6705 does not support bands and channels, only frequencies.
|
||||
//therefore always return 0
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool vtxRTC6705GetPowerIndex(const vtxDevice_t *vtxDevice, uint8_t *pIndex)
|
||||
{
|
||||
*pIndex = vtxDevice->powerIndex;
|
||||
UNUSED(vtxDevice);
|
||||
*pIndex = rtc6705PowerIndex;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -208,7 +221,8 @@ static bool vtxRTC6705GetPitMode(const vtxDevice_t *vtxDevice, uint8_t *pOnOff)
|
|||
|
||||
static bool vtxRTC6705GetFreq(const vtxDevice_t *vtxDevice, uint16_t *pFrequency)
|
||||
{
|
||||
*pFrequency = vtxDevice->frequency;
|
||||
UNUSED(vtxDevice);
|
||||
*pFrequency = rtc6705Frequency;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
|
@ -46,7 +46,6 @@
|
|||
#include "io/vtx.h"
|
||||
#include "io/vtx_control.h"
|
||||
#include "io/vtx_smartaudio.h"
|
||||
#include "io/vtx_string.h"
|
||||
|
||||
|
||||
// Timing parameters
|
||||
|
@ -92,9 +91,9 @@ enum {
|
|||
|
||||
|
||||
// convert between 'saDevice.channel' and band/channel values
|
||||
#define SA_DEVICE_CHVAL_TO_BAND(val) ((val) / (uint8_t)8)
|
||||
#define SA_DEVICE_CHVAL_TO_CHANNEL(val) ((val) % (uint8_t)8)
|
||||
#define SA_BANDCHAN_TO_DEVICE_CHVAL(band, channel) ((band) * (uint8_t)8 + (channel))
|
||||
#define SA_DEVICE_CHVAL_TO_BAND(val) ((val) / (uint8_t)vtxTableChannelCount) + 1
|
||||
#define SA_DEVICE_CHVAL_TO_CHANNEL(val) ((val) % (uint8_t)vtxTableChannelCount) + 1
|
||||
#define SA_BANDCHAN_TO_DEVICE_CHVAL(band, channel) ((band - 1) * (uint8_t)vtxTableChannelCount + (channel - 1))
|
||||
|
||||
|
||||
// Statistical counters, for user side trouble shooting.
|
||||
|
@ -118,6 +117,7 @@ smartAudioDevice_t saDevice = {
|
|||
.mode = 0,
|
||||
.freq = 0,
|
||||
.orfreq = 0,
|
||||
.willBootIntoPitMode = false,
|
||||
};
|
||||
|
||||
static smartAudioDevice_t saDevicePrev = {
|
||||
|
@ -139,7 +139,7 @@ bool saDeferred = true; // saCms variable?
|
|||
|
||||
// Receive frame reassembly buffer
|
||||
#define SA_MAX_RCVLEN 21
|
||||
static uint8_t sa_rbuf[SA_MAX_RCVLEN+4]; // XXX delete 4 byte guard
|
||||
static uint8_t sa_rbuf[SA_MAX_RCVLEN + 4]; // XXX delete 4 byte guard
|
||||
|
||||
//
|
||||
// CRC8 computations
|
||||
|
@ -182,9 +182,9 @@ static void saPrintSettings(void)
|
|||
dprintf((" channel: %d ", saDevice.channel));
|
||||
dprintf(("freq: %d ", saDevice.freq));
|
||||
dprintf(("power: %d ", saDevice.power));
|
||||
dprintf(("powerval: %d ",saDevice.power > 0 ? vtxSmartAudio.powerValues[saDevice.power - 1] : -1));
|
||||
dprintf(("powerval: %d ", saDevice.power > 0 ? vtxTablePowerValues[saDevice.power - 1] : -1));
|
||||
dprintf(("pitfreq: %d ", saDevice.orfreq));
|
||||
dprintf(("device %s boot into pitmode ", saDevice.willBootIntoPitMode ? "will" : "will not"));
|
||||
dprintf(("BootIntoPitMode: %s ", saDevice.willBootIntoPitMode ? "yes" : "no"));
|
||||
dprintf(("\r\n"));
|
||||
}
|
||||
#endif
|
||||
|
@ -281,7 +281,7 @@ static void saProcessResponse(uint8_t *buf, int len)
|
|||
saDevice.channel = buf[2];
|
||||
uint8_t rawPowerValue = buf[3];
|
||||
saDevice.mode = buf[4];
|
||||
saDevice.freq = (buf[5] << 8)|buf[6];
|
||||
saDevice.freq = (buf[5] << 8) | buf[6];
|
||||
|
||||
// read pir and por flags to detect if the device will boot into pitmode.
|
||||
// note that "quit pitmode without unsetting the pitmode flag" clears pir and por flags but the device will still boot into pitmode.
|
||||
|
@ -291,15 +291,15 @@ static void saProcessResponse(uint8_t *buf, int len)
|
|||
if (saDevice.mode & SA_MODE_GET_PITMODE) {
|
||||
bool newBootMode = (saDevice.mode & SA_MODE_GET_IN_RANGE_PITMODE) || (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE);
|
||||
if (newBootMode != saDevice.willBootIntoPitMode) {
|
||||
dprintf(("saProcessResponse: willBootIntoPitMode is now %s\r\n", saDevice.willBootIntoPitMode ? "true" : "false"));
|
||||
dprintf(("saProcessResponse: willBootIntoPitMode is now %s\r\n", newBootMode ? "true" : "false"));
|
||||
}
|
||||
saDevice.willBootIntoPitMode = newBootMode;
|
||||
}
|
||||
|
||||
if(saDevice.version == 3) {
|
||||
if (saDevice.version == 3) {
|
||||
//read dbm based power levels
|
||||
//aaaaaand promptly forget them. todo: write them into vtxtable pg and load it
|
||||
if(len < 10) {//current power level in dbm field missing or power level length field missing or zero power levels reported
|
||||
if (len < 10) { //current power level in dbm field missing or power level length field missing or zero power levels reported
|
||||
dprintf(("processResponse: V2.1 vtx didn't report any power levels\r\n"));
|
||||
break;
|
||||
}
|
||||
|
@ -323,8 +323,8 @@ static void saProcessResponse(uint8_t *buf, int len)
|
|||
}
|
||||
|
||||
dprintf(("processResponse: %d power values: %d, %d, %d, %d\r\n",
|
||||
vtxSmartAudio.capability.powerCount, vtxSmartAudio.powerValues[0], vtxSmartAudio.powerValues[1],
|
||||
vtxSmartAudio.powerValues[2], vtxSmartAudio.powerValues[3]));
|
||||
vtxTablePowerLevels, vtxTablePowerValues[0], vtxTablePowerValues[1],
|
||||
vtxTablePowerValues[2], vtxTablePowerValues[3]));
|
||||
//dprintf(("processResponse: V2.1 received vtx power value %d\r\n",buf[7]));
|
||||
rawPowerValue = buf[7];
|
||||
}
|
||||
|
@ -333,8 +333,8 @@ static void saProcessResponse(uint8_t *buf, int len)
|
|||
#endif
|
||||
saDevice.power = 0;//set to unknown power level if the reported one doesnt match any of the known ones
|
||||
dprintf(("processResponse: rawPowerValue is %d, legacy power is %d\r\n", rawPowerValue, buf[3]));
|
||||
for (int8_t i = 0; i < vtxSmartAudio.capability.powerCount; i++) {
|
||||
if(rawPowerValue == vtxSmartAudio.powerValues[i]) {
|
||||
for (int8_t i = 0; i < vtxTablePowerLevels; i++) {
|
||||
if (rawPowerValue == vtxTablePowerValues[i]) {
|
||||
#ifdef USE_SMARTAUDIO_DPRINTF
|
||||
if (prevPower != i + 1) {
|
||||
dprintf(("processResponse: power changed from index %d to index %d\r\n", prevPower, i + 1));
|
||||
|
@ -362,7 +362,7 @@ static void saProcessResponse(uint8_t *buf, int len)
|
|||
break;
|
||||
}
|
||||
|
||||
const uint16_t freq = (buf[2] << 8)|buf[3];
|
||||
const uint16_t freq = (buf[2] << 8) | buf[3];
|
||||
|
||||
if (freq & SA_FREQ_GETPIT) {
|
||||
saDevice.orfreq = freq & SA_FREQ_MASK;
|
||||
|
@ -609,7 +609,7 @@ static bool saValidateFreq(uint16_t freq)
|
|||
return (freq >= VTX_SMARTAUDIO_MIN_FREQUENCY_MHZ && freq <= VTX_SMARTAUDIO_MAX_FREQUENCY_MHZ);
|
||||
}
|
||||
|
||||
static void saDoDevSetFreq(uint16_t freq)
|
||||
void saSetFreq(uint16_t freq)
|
||||
{
|
||||
static uint8_t buf[7] = { 0xAA, 0x55, SACMD(SA_CMD_SET_FREQ), 2 };
|
||||
static uint8_t switchBuf[7];
|
||||
|
@ -645,14 +645,9 @@ static void saDoDevSetFreq(uint16_t freq)
|
|||
saQueueCmd(buf, 7);
|
||||
}
|
||||
|
||||
void saSetFreq(uint16_t freq)
|
||||
{
|
||||
saDoDevSetFreq(freq);
|
||||
}
|
||||
|
||||
void saSetPitFreq(uint16_t freq)
|
||||
{
|
||||
saDoDevSetFreq(freq | SA_FREQ_SETPIT);
|
||||
saSetFreq(freq | SA_FREQ_SETPIT);
|
||||
}
|
||||
|
||||
#if 0
|
||||
|
@ -662,34 +657,12 @@ static void saGetPitFreq(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
static bool saValidateBandAndChannel(uint8_t band, uint8_t channel)
|
||||
{
|
||||
return (band >= VTX_SMARTAUDIO_MIN_BAND && band <= VTX_SMARTAUDIO_MAX_BAND &&
|
||||
channel >= VTX_SMARTAUDIO_MIN_CHANNEL && channel <= VTX_SMARTAUDIO_MAX_CHANNEL);
|
||||
}
|
||||
|
||||
static void saDevSetBandAndChannel(uint8_t band, uint8_t channel)
|
||||
{
|
||||
static uint8_t buf[6] = { 0xAA, 0x55, SACMD(SA_CMD_SET_CHAN), 1 };
|
||||
|
||||
buf[4] = SA_BANDCHAN_TO_DEVICE_CHVAL(band, channel);
|
||||
buf[5] = CRC8(buf, 5);
|
||||
dprintf(("saDevSetBandAndChannel band %d channel %d value sent 0x%x", band, channel, buf[4]));
|
||||
|
||||
saQueueCmd(buf, 6);
|
||||
}
|
||||
|
||||
void saSetBandAndChannel(uint8_t band, uint8_t channel)
|
||||
{
|
||||
saDevSetBandAndChannel(band, channel);
|
||||
}
|
||||
|
||||
void saSetMode(int mode)
|
||||
{
|
||||
static uint8_t buf[6] = { 0xAA, 0x55, SACMD(SA_CMD_SET_MODE), 1 };
|
||||
|
||||
buf[4] = (mode & 0x3f)|saLockMode;
|
||||
if (saDevice.version>=3 && (mode & SA_MODE_CLR_PITMODE) &&
|
||||
buf[4] = (mode & 0x3f) | saLockMode;
|
||||
if (saDevice.version >= 3 && (mode & SA_MODE_CLR_PITMODE) &&
|
||||
((mode & SA_MODE_SET_IN_RANGE_PITMODE) || (mode & SA_MODE_SET_OUT_RANGE_PITMODE))) {
|
||||
saDevice.willBootIntoPitMode = true;//quit pitmode without unsetting flag.
|
||||
//the response will just say pit=off but the device will still go into pitmode on reboot.
|
||||
|
@ -736,33 +709,18 @@ bool vtxSmartAudioInit(void)
|
|||
return false;
|
||||
}
|
||||
|
||||
for(int8_t i = 0; i < VTX_SMARTAUDIO_POWER_COUNT; i++) {
|
||||
for (int8_t i = 0; i < VTX_SMARTAUDIO_POWER_COUNT; i++) {
|
||||
saSupportedPowerValues[i] = 1;
|
||||
}
|
||||
|
||||
#ifdef USE_VTX_TABLE
|
||||
vtxSmartAudio.capability.bandCount = vtxTableBandCount;
|
||||
vtxSmartAudio.capability.channelCount = vtxTableChannelCount;
|
||||
vtxSmartAudio.capability.powerCount = vtxTablePowerLevels;
|
||||
vtxSmartAudio.frequencyTable = (uint16_t *)vtxTableFrequency;
|
||||
vtxSmartAudio.bandNames = vtxTableBandNames;
|
||||
vtxSmartAudio.bandLetters = vtxTableBandLetters;
|
||||
vtxSmartAudio.channelNames = vtxTableChannelNames;
|
||||
vtxSmartAudio.powerNames = vtxTablePowerLabels;
|
||||
vtxSmartAudio.powerValues = vtxTablePowerValues;
|
||||
#else
|
||||
vtxSmartAudio.capability.bandCount = VTX_SMARTAUDIO_BAND_COUNT;
|
||||
vtxSmartAudio.capability.channelCount = VTX_SMARTAUDIO_CHANNEL_COUNT;
|
||||
vtxSmartAudio.capability.powerCount = saSupportedNumPowerLevels,
|
||||
vtxSmartAudio.frequencyTable = vtxStringFrequencyTable();
|
||||
vtxSmartAudio.bandNames = vtxStringBandNames();
|
||||
vtxSmartAudio.bandLetters = vtxStringBandLetters();
|
||||
vtxSmartAudio.channelNames = vtxStringChannelNames();
|
||||
vtxSmartAudio.powerNames = (const char**)saSupportedPowerLabelPointerArray;
|
||||
vtxSmartAudio.powerValues = saSupportedPowerValues;
|
||||
#endif
|
||||
dprintf(("vtxSmartAudioInit %d power levels recorded\r\n", vtxTablePowerLevels));
|
||||
|
||||
|
||||
|
||||
vtxCommonSetDevice(&vtxSmartAudio);
|
||||
#ifndef USE_VTX_TABLE
|
||||
vtxTableSetFactoryBands(true);
|
||||
#endif
|
||||
|
||||
vtxInit();
|
||||
|
||||
|
@ -806,7 +764,7 @@ static void vtxSAProcess(vtxDevice_t *vtxDevice, timeUs_t currentTimeUs)
|
|||
// Also don't send it to V2.1 for the same reason.
|
||||
if (saDevice.version) {
|
||||
if (saDevice.version == 2) {
|
||||
saDoDevSetFreq(SA_FREQ_GETPIT);
|
||||
saSetFreq(SA_FREQ_GETPIT);
|
||||
initPhase = SA_INITPHASE_WAIT_PITFREQ;
|
||||
} else {
|
||||
initPhase = SA_INITPHASE_DONE;
|
||||
|
@ -818,20 +776,28 @@ static void vtxSAProcess(vtxDevice_t *vtxDevice, timeUs_t currentTimeUs)
|
|||
saSupportedPowerValues[1] = 16;
|
||||
saSupportedPowerValues[2] = 25;
|
||||
saSupportedPowerValues[3] = 40;
|
||||
}else if(saDevice.version == 2) {
|
||||
} else if (saDevice.version == 2) {
|
||||
saSupportedPowerValues[0] = 0;
|
||||
saSupportedPowerValues[1] = 1;
|
||||
saSupportedPowerValues[2] = 2;
|
||||
saSupportedPowerValues[3] = 3;
|
||||
}
|
||||
|
||||
if (saDevice.version >= 2) {//V2.0 and V1.0 use defaults set at declaration
|
||||
vtxSmartAudio.capability.powerCount = constrain(saSupportedNumPowerLevels, 0, VTX_SMARTAUDIO_POWER_COUNT);
|
||||
for(int8_t i = 0; i < saSupportedNumPowerLevels; i++) {
|
||||
tfp_sprintf(saSupportedPowerLabels[i + 1], "%3d", constrain(saSupportedPowerValues[i], 0, 999));
|
||||
//without USE_VTX_TABLE, fill vtxTable variables with default settings (instead of loading them from PG)
|
||||
vtxTablePowerLevels = constrain(saSupportedNumPowerLevels, 0, VTX_SMARTAUDIO_POWER_COUNT);
|
||||
if (saDevice.version >= 3) {
|
||||
for (int8_t i = 0; i < vtxTablePowerLevels; i++) {
|
||||
//ideally we would convert dbm to mW here
|
||||
tfp_sprintf(saSupportedPowerLabels[i + 1], "%3d", constrain(saSupportedPowerValues[i], 0, 999));
|
||||
}
|
||||
}
|
||||
for (int8_t i = 0; i < vtxTablePowerLevels; i++) {
|
||||
vtxTablePowerValues[i] = saSupportedPowerValues[i];
|
||||
}
|
||||
for (int8_t i = 0; i < vtxTablePowerLevels + 1; i++) {
|
||||
vtxTablePowerLabels[i] = saSupportedPowerLabels[i];
|
||||
}
|
||||
dprintf(("vtxSAProcess init phase vtxTablePowerLevels set to %d\r\n", vtxTablePowerLevels));
|
||||
#endif
|
||||
|
||||
if (saDevice.version >= 2 ) {
|
||||
|
@ -868,7 +834,8 @@ static void vtxSAProcess(vtxDevice_t *vtxDevice, timeUs_t currentTimeUs)
|
|||
dprintf(("process: sending queue\r\n"));
|
||||
saSendQueue();
|
||||
lastCommandSentMs = nowMs;
|
||||
} else if ((nowMs - lastCommandSentMs < SMARTAUDIO_POLLING_WINDOW) && (nowMs - sa_lastTransmissionMs >= SMARTAUDIO_POLLING_INTERVAL)) {
|
||||
} else if ((nowMs - lastCommandSentMs < SMARTAUDIO_POLLING_WINDOW)
|
||||
&& (nowMs - sa_lastTransmissionMs >= SMARTAUDIO_POLLING_INTERVAL)) {
|
||||
dprintf(("process: sending status change polling\r\n"));
|
||||
saGetSettings();
|
||||
saSendQueue();
|
||||
|
@ -885,14 +852,39 @@ vtxDevType_e vtxSAGetDeviceType(const vtxDevice_t *vtxDevice)
|
|||
|
||||
static bool vtxSAIsReady(const vtxDevice_t *vtxDevice)
|
||||
{
|
||||
return vtxDevice!=NULL && !(saDevice.version == 0);
|
||||
#ifndef USE_VTX_TABLE
|
||||
if (vtxDevice != NULL && saDevice.power == 0) {
|
||||
return false;
|
||||
//wait until power reading exists
|
||||
//this is needed bc the powervalues are loaded into vtxTableXXX after the first settings are received
|
||||
//thus the first time processResponse runs its index lookup it won't find anything and no power is recorded
|
||||
//this waits until after the second time settings are received which will actually find something
|
||||
//this check is not needed with USE_VTX_TABLE as the table is loaded from pg before smartaudio is even started
|
||||
//in fact, with USE_VTX_TABLE this check could end up paralyzing the smartaudio implementation if the user has
|
||||
//chosen to omit a power state in the vtxtable but the vtx happens to power up in that state for whatever reason
|
||||
}
|
||||
#endif
|
||||
return vtxDevice != NULL && saDevice.version != 0;
|
||||
}
|
||||
|
||||
static bool saValidateBandAndChannel(uint8_t band, uint8_t channel)
|
||||
{
|
||||
return (band >= VTX_SMARTAUDIO_MIN_BAND && band <= vtxTableBandCount &&
|
||||
channel >= VTX_SMARTAUDIO_MIN_CHANNEL && channel <= vtxTableChannelCount);
|
||||
}
|
||||
|
||||
static void vtxSASetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channel)
|
||||
{
|
||||
UNUSED(vtxDevice);
|
||||
if (saValidateBandAndChannel(band, channel)) {
|
||||
saSetBandAndChannel(band - 1, channel - 1);
|
||||
static uint8_t buf[6] = { 0xAA, 0x55, SACMD(SA_CMD_SET_CHAN), 1 };
|
||||
|
||||
buf[4] = SA_BANDCHAN_TO_DEVICE_CHVAL(band, channel);
|
||||
buf[5] = CRC8(buf, 5);
|
||||
dprintf(("vtxSASetBandAndChannel set index band %d channel %d value sent 0x%x\r\n", band, channel, buf[4]));
|
||||
|
||||
//this will clear saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ
|
||||
saQueueCmd(buf, 6);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -904,12 +896,14 @@ static void vtxSASetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index)
|
|||
return;
|
||||
}
|
||||
|
||||
if (index <= 0 || index > vtxSmartAudio.capability.powerCount) {
|
||||
dprintf(("saSetPowerByIndex: cannot get power level %d, only levels 1 through %d supported", index, vtxSmartAudio.capability.powerCount));
|
||||
uint16_t powerValue = 0;
|
||||
if (!vtxCommonLookupPowerValue(vtxDevice, index, &powerValue)) {
|
||||
dprintf(("saSetPowerByIndex: cannot get power level %d, only levels 1 through %d supported", index,
|
||||
vtxTablePowerLevels));
|
||||
return;
|
||||
}
|
||||
|
||||
buf[4] = vtxSmartAudio.powerValues[index - 1];//use vtxcommonlookuppowervalue instead?
|
||||
buf[4] = powerValue;
|
||||
dprintf(("saSetPowerByIndex: index %d, value %d\r\n", index, buf[4]));
|
||||
if (saDevice.version == 3) {
|
||||
buf[4] |= 128;//set MSB to indicate set power by dbm
|
||||
|
@ -929,7 +923,7 @@ static void vtxSASetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff)
|
|||
return;
|
||||
}
|
||||
|
||||
if(saDevice.version >= 3 && !saDevice.willBootIntoPitMode) {
|
||||
if (saDevice.version >= 3 && !saDevice.willBootIntoPitMode) {
|
||||
if (onoff) {
|
||||
// enable pitmode using SET_POWER command with 0 dbm.
|
||||
// This enables pitmode without causing the device to boot into pitmode next power-up
|
||||
|
@ -967,9 +961,11 @@ static void vtxSASetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff)
|
|||
|
||||
static void vtxSASetFreq(vtxDevice_t *vtxDevice, uint16_t freq)
|
||||
{
|
||||
UNUSED(vtxDevice);
|
||||
if (!vtxSAIsReady(vtxDevice)) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (saValidateFreq(freq)) {
|
||||
saSetMode(0); //need to be in FREE mode to set freq
|
||||
saSetFreq(freq);
|
||||
}
|
||||
}
|
||||
|
@ -980,11 +976,15 @@ static bool vtxSAGetBandAndChannel(const vtxDevice_t *vtxDevice, uint8_t *pBand,
|
|||
return false;
|
||||
}
|
||||
|
||||
// if in user-freq mode then report band as zero
|
||||
*pBand = (saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ) ? 0 :
|
||||
(SA_DEVICE_CHVAL_TO_BAND(saDevice.channel) + 1);
|
||||
*pChannel = SA_DEVICE_CHVAL_TO_CHANNEL(saDevice.channel) + 1;
|
||||
if (saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ) {
|
||||
*pBand = 0;
|
||||
*pChannel = 0;
|
||||
return true;
|
||||
} else {
|
||||
*pBand = SA_DEVICE_CHVAL_TO_BAND(saDevice.channel);
|
||||
*pChannel = SA_DEVICE_CHVAL_TO_CHANNEL(saDevice.channel);
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
static bool vtxSAGetPowerIndex(const vtxDevice_t *vtxDevice, uint8_t *pIndex)
|
||||
|
@ -1016,8 +1016,8 @@ static bool vtxSAGetFreq(const vtxDevice_t *vtxDevice, uint16_t *pFreq)
|
|||
// if not in user-freq mode then convert band/chan to frequency
|
||||
*pFreq = (saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ) ? saDevice.freq :
|
||||
vtxCommonLookupFrequency(&vtxSmartAudio,
|
||||
SA_DEVICE_CHVAL_TO_BAND(saDevice.channel) + 1,
|
||||
SA_DEVICE_CHVAL_TO_CHANNEL(saDevice.channel) + 1);
|
||||
SA_DEVICE_CHVAL_TO_BAND(saDevice.channel),
|
||||
SA_DEVICE_CHVAL_TO_CHANNEL(saDevice.channel));
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
|
@ -25,7 +25,6 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
//#define USE_SMARTAUDIO_DPRINTF
|
||||
#ifdef USE_SMARTAUDIO_DPRINTF
|
||||
#include "io/serial.h"
|
||||
#include "common/printf.h"
|
||||
|
@ -33,15 +32,10 @@
|
|||
#endif
|
||||
|
||||
#define VTX_SMARTAUDIO_MIN_BAND 1
|
||||
#define VTX_SMARTAUDIO_MAX_BAND 5
|
||||
#define VTX_SMARTAUDIO_MIN_CHANNEL 1
|
||||
#define VTX_SMARTAUDIO_MAX_CHANNEL 8
|
||||
|
||||
#define VTX_SMARTAUDIO_BAND_COUNT (VTX_SMARTAUDIO_MAX_BAND - VTX_SMARTAUDIO_MIN_BAND + 1)
|
||||
#define VTX_SMARTAUDIO_CHANNEL_COUNT (VTX_SMARTAUDIO_MAX_CHANNEL - VTX_SMARTAUDIO_MIN_CHANNEL + 1)
|
||||
|
||||
#define VTX_SMARTAUDIO_POWER_COUNT 4
|
||||
#define VTX_SMARTAUDIO_DEFAULT_POWER 1
|
||||
|
||||
#define VTX_SMARTAUDIO_MIN_FREQUENCY_MHZ 5000 //min freq in MHz
|
||||
#define VTX_SMARTAUDIO_MAX_FREQUENCY_MHZ 5999 //max freq in MHz
|
||||
|
@ -95,7 +89,6 @@ extern smartAudioStat_t saStat;
|
|||
extern uint16_t sa_smartbaud;
|
||||
extern bool saDeferred;
|
||||
|
||||
void saSetBandAndChannel(uint8_t band, uint8_t channel);
|
||||
void saSetMode(int mode);
|
||||
void saSetFreq(uint16_t freq);
|
||||
void saSetPitFreq(uint16_t freq);
|
||||
|
|
|
@ -1,79 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
/* Created by jflyper */
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#if defined(USE_VTX_COMMON)
|
||||
|
||||
#define VTX_STRING_BAND_COUNT 5
|
||||
#define VTX_STRING_CHAN_COUNT 8
|
||||
|
||||
static const uint16_t vtx58frequencyTable[VTX_STRING_BAND_COUNT][VTX_STRING_CHAN_COUNT] =
|
||||
{
|
||||
{ 5865, 5845, 5825, 5805, 5785, 5765, 5745, 5725 }, // Boscam A
|
||||
{ 5733, 5752, 5771, 5790, 5809, 5828, 5847, 5866 }, // Boscam B
|
||||
{ 5705, 5685, 5665, 5645, 5885, 5905, 5925, 5945 }, // Boscam E
|
||||
{ 5740, 5760, 5780, 5800, 5820, 5840, 5860, 5880 }, // FatShark
|
||||
{ 5658, 5695, 5732, 5769, 5806, 5843, 5880, 5917 }, // RaceBand
|
||||
};
|
||||
|
||||
static const char * vtx58BandNames[] = {
|
||||
"--------",
|
||||
"BOSCAM A",
|
||||
"BOSCAM B",
|
||||
"BOSCAM E",
|
||||
"FATSHARK",
|
||||
"RACEBAND",
|
||||
};
|
||||
|
||||
static char const vtx58BandLetter[] = "-ABEFR";
|
||||
|
||||
static char const * vtx58ChannelNames[] = {
|
||||
"-", "1", "2", "3", "4", "5", "6", "7", "8",
|
||||
};
|
||||
|
||||
const uint16_t *vtxStringFrequencyTable(void)
|
||||
{
|
||||
return &vtx58frequencyTable[0][0];
|
||||
}
|
||||
|
||||
const char **vtxStringBandNames(void)
|
||||
{
|
||||
return vtx58BandNames;
|
||||
}
|
||||
|
||||
const char **vtxStringChannelNames(void)
|
||||
{
|
||||
return vtx58ChannelNames;
|
||||
}
|
||||
|
||||
const char *vtxStringBandLetters(void)
|
||||
{
|
||||
return vtx58BandLetter;
|
||||
}
|
||||
|
||||
#endif
|
|
@ -1,34 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "drivers/vtx_common.h"
|
||||
|
||||
bool _vtxStringFreq2Bandchan(uint16_t freq, uint8_t *pBand, uint8_t *pChannel);
|
||||
uint16_t _vtxStringBandchan2Freq(uint8_t band, uint8_t channel);
|
||||
|
||||
const uint16_t * vtxStringFrequencyTable(void);
|
||||
const char ** vtxStringBandNames(void);
|
||||
const char ** vtxStringChannelNames(void);
|
||||
const char * vtxStringBandLetters(void);
|
|
@ -37,23 +37,19 @@
|
|||
#include "cms/cms_menu_vtx_tramp.h"
|
||||
|
||||
#include "drivers/vtx_common.h"
|
||||
|
||||
#ifdef USE_VTX_TABLE
|
||||
#include "drivers/vtx_table.h"
|
||||
#endif
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/vtx_tramp.h"
|
||||
#include "io/vtx_control.h"
|
||||
#include "io/vtx.h"
|
||||
#include "io/vtx_string.h"
|
||||
|
||||
#if defined(USE_CMS) || defined(USE_VTX_COMMON)
|
||||
#if (defined(USE_CMS) || defined(USE_VTX_COMMON)) && !defined(USE_VTX_TABLE)
|
||||
const uint16_t trampPowerTable[VTX_TRAMP_POWER_COUNT] = {
|
||||
25, 100, 200, 400, 600
|
||||
};
|
||||
|
||||
const char * trampPowerNames[VTX_TRAMP_POWER_COUNT+1] = {
|
||||
const char *trampPowerNames[VTX_TRAMP_POWER_COUNT + 1] = {
|
||||
"---", "25 ", "100", "200", "400", "600"
|
||||
};
|
||||
#endif
|
||||
|
@ -84,10 +80,7 @@ uint32_t trampRFFreqMin;
|
|||
uint32_t trampRFFreqMax;
|
||||
uint32_t trampRFPowerMax;
|
||||
|
||||
bool trampSetByFreqFlag = false; //false = set via band/channel
|
||||
uint32_t trampCurFreq = 0;
|
||||
uint8_t trampBand = 0;
|
||||
uint8_t trampChannel = 0;
|
||||
uint16_t trampPower = 0; // Actual transmitting power
|
||||
uint16_t trampConfiguredPower = 0; // Configured transmitting power
|
||||
int16_t trampTemperature = 0;
|
||||
|
@ -148,7 +141,6 @@ static void trampDevSetFreq(uint16_t freq)
|
|||
|
||||
void trampSetFreq(uint16_t freq)
|
||||
{
|
||||
trampSetByFreqFlag = true; //set freq via MHz value
|
||||
trampDevSetFreq(freq);
|
||||
}
|
||||
|
||||
|
@ -157,23 +149,6 @@ void trampSendFreq(uint16_t freq)
|
|||
trampCmdU16('F', freq);
|
||||
}
|
||||
|
||||
static bool trampValidateBandAndChannel(uint8_t band, uint8_t channel)
|
||||
{
|
||||
return (band >= VTX_TRAMP_MIN_BAND && band <= VTX_TRAMP_MAX_BAND &&
|
||||
channel >= VTX_TRAMP_MIN_CHANNEL && channel <= VTX_TRAMP_MAX_CHANNEL);
|
||||
}
|
||||
|
||||
static void trampDevSetBandAndChannel(uint8_t band, uint8_t channel)
|
||||
{
|
||||
trampDevSetFreq(vtxCommonLookupFrequency(&vtxTramp, band, channel));
|
||||
}
|
||||
|
||||
void trampSetBandAndChannel(uint8_t band, uint8_t channel)
|
||||
{
|
||||
trampSetByFreqFlag = false; //set freq via band/channel
|
||||
trampDevSetBandAndChannel(band, channel);
|
||||
}
|
||||
|
||||
void trampSetRFPower(uint16_t level)
|
||||
{
|
||||
trampConfPower = level;
|
||||
|
@ -198,17 +173,6 @@ bool trampCommitChanges(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
// return false if index out of range
|
||||
static bool trampDevSetPowerByIndex(uint8_t index)
|
||||
{
|
||||
if (index > 0 && index <= vtxTramp.capability.powerCount) {
|
||||
trampSetRFPower(vtxTramp.powerValues[index - 1]);
|
||||
trampCommitChanges();
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void trampSetPitMode(uint8_t onoff)
|
||||
{
|
||||
trampCmdU16('I', onoff ? 0 : 1);
|
||||
|
@ -243,11 +207,6 @@ static char trampHandleResponse(void)
|
|||
trampPitMode = trampRespBuffer[7];
|
||||
trampPower = trampRespBuffer[8]|(trampRespBuffer[9] << 8);
|
||||
|
||||
// if no band/chan match then make sure set-by-freq mode is flagged
|
||||
if (!vtxCommonLookupBandChan(&vtxTramp, trampCurFreq, &trampBand, &trampChannel)) {
|
||||
trampSetByFreqFlag = true;
|
||||
}
|
||||
|
||||
if (trampConfFreq == 0) trampConfFreq = trampCurFreq;
|
||||
if (trampConfPower == 0) trampConfPower = trampPower;
|
||||
return 'v';
|
||||
|
@ -500,22 +459,24 @@ static vtxDevType_e vtxTrampGetDeviceType(const vtxDevice_t *vtxDevice)
|
|||
|
||||
static bool vtxTrampIsReady(const vtxDevice_t *vtxDevice)
|
||||
{
|
||||
return vtxDevice!=NULL && trampStatus > TRAMP_STATUS_OFFLINE;
|
||||
return vtxDevice != NULL && trampStatus > TRAMP_STATUS_OFFLINE;
|
||||
}
|
||||
|
||||
static void vtxTrampSetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channel)
|
||||
{
|
||||
UNUSED(vtxDevice);
|
||||
if (trampValidateBandAndChannel(band, channel)) {
|
||||
trampSetBandAndChannel(band, channel);
|
||||
trampCommitChanges();
|
||||
}
|
||||
UNUSED(band);
|
||||
UNUSED(channel);
|
||||
//tramp does not support band/channel mode, only frequency
|
||||
}
|
||||
|
||||
static void vtxTrampSetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index)
|
||||
{
|
||||
UNUSED(vtxDevice);
|
||||
trampDevSetPowerByIndex(index);
|
||||
uint16_t powerValue = 0;
|
||||
if (vtxCommonLookupPowerValue(vtxDevice, index, &powerValue)) {
|
||||
trampSetRFPower(powerValue);
|
||||
trampCommitChanges();
|
||||
}
|
||||
}
|
||||
|
||||
static void vtxTrampSetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff)
|
||||
|
@ -539,9 +500,9 @@ static bool vtxTrampGetBandAndChannel(const vtxDevice_t *vtxDevice, uint8_t *pBa
|
|||
return false;
|
||||
}
|
||||
|
||||
// if in user-freq mode then report band as zero
|
||||
*pBand = trampSetByFreqFlag ? 0 : trampBand;
|
||||
*pChannel = trampChannel;
|
||||
// tramp does not support band and channel
|
||||
*pBand = 0;
|
||||
*pChannel = 0;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -552,8 +513,8 @@ static bool vtxTrampGetPowerIndex(const vtxDevice_t *vtxDevice, uint8_t *pIndex)
|
|||
}
|
||||
|
||||
if (trampConfiguredPower > 0) {
|
||||
for (uint8_t i = 0; i < vtxTramp.capability.powerCount; i++) {
|
||||
if (trampConfiguredPower <= vtxTramp.powerValues[i]) {
|
||||
for (uint8_t i = 0; i < vtxTablePowerLevels; i++) {
|
||||
if (trampConfiguredPower <= vtxTablePowerValues[i]) {
|
||||
*pIndex = i + 1;
|
||||
break;
|
||||
}
|
||||
|
@ -620,29 +581,19 @@ bool vtxTrampInit(void)
|
|||
|
||||
// XXX Effect of USE_VTX_COMMON should be reviewed, as following call to vtxInit will do nothing if vtxCommonSetDevice is not called.
|
||||
#if defined(USE_VTX_COMMON)
|
||||
#if defined(USE_VTX_TABLE)
|
||||
vtxTramp.capability.bandCount = vtxTableBandCount;
|
||||
vtxTramp.capability.channelCount = vtxTableChannelCount;
|
||||
vtxTramp.capability.powerCount = vtxTablePowerLevels;
|
||||
vtxTramp.frequencyTable = (uint16_t *)vtxTableFrequency;
|
||||
vtxTramp.bandNames = vtxTableBandNames;
|
||||
vtxTramp.bandLetters = vtxTableBandLetters;
|
||||
vtxTramp.channelNames = vtxTableChannelNames;
|
||||
vtxTramp.powerNames = vtxTablePowerLabels;
|
||||
vtxTramp.powerValues = vtxTablePowerValues;
|
||||
#else
|
||||
vtxTramp.capability.bandCount = VTX_TRAMP_BAND_COUNT;
|
||||
vtxTramp.capability.channelCount = VTX_TRAMP_CHANNEL_COUNT;
|
||||
vtxTramp.capability.powerCount = sizeof(trampPowerTable),
|
||||
vtxTramp.frequencyTable = vtxStringFrequencyTable();
|
||||
vtxTramp.bandNames = vtxStringBandNames();
|
||||
vtxTramp.bandLetters = vtxStringBandLetters();
|
||||
vtxTramp.channelNames = vtxStringChannelNames();
|
||||
vtxTramp.powerNames = trampPowerNames;
|
||||
vtxTramp.powerValues = trampPowerTable;
|
||||
#endif
|
||||
|
||||
vtxCommonSetDevice(&vtxTramp);
|
||||
#ifndef USE_VTX_TABLE
|
||||
//without USE_VTX_TABLE, fill vtxTable variables with default settings (instead of loading them from PG)
|
||||
vtxTablePowerLevels = VTX_TRAMP_POWER_COUNT;
|
||||
for (int i = 0; i < VTX_TRAMP_POWER_COUNT + 1; i++) {
|
||||
vtxTablePowerLabels[i] = trampPowerNames[i];
|
||||
}
|
||||
for (int i = 0; i < VTX_TRAMP_POWER_COUNT; i++) {
|
||||
vtxTablePowerValues[i] = trampPowerTable[i];
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
|
|
|
@ -22,16 +22,7 @@
|
|||
|
||||
#include <stdint.h>
|
||||
|
||||
#define VTX_TRAMP_MIN_BAND 1
|
||||
#define VTX_TRAMP_MAX_BAND 5
|
||||
#define VTX_TRAMP_MIN_CHANNEL 1
|
||||
#define VTX_TRAMP_MAX_CHANNEL 8
|
||||
|
||||
#define VTX_TRAMP_BAND_COUNT (VTX_TRAMP_MAX_BAND - VTX_TRAMP_MIN_BAND + 1)
|
||||
#define VTX_TRAMP_CHANNEL_COUNT (VTX_TRAMP_MAX_CHANNEL - VTX_TRAMP_MIN_CHANNEL + 1)
|
||||
|
||||
#define VTX_TRAMP_POWER_COUNT 5
|
||||
#define VTX_TRAMP_DEFAULT_POWER 1
|
||||
|
||||
#define VTX_TRAMP_MIN_FREQUENCY_MHZ 5000 //min freq in MHz
|
||||
#define VTX_TRAMP_MAX_FREQUENCY_MHZ 5999 //max freq in MHz
|
||||
|
|
|
@ -92,7 +92,6 @@
|
|||
#include "io/usb_msc.h"
|
||||
#include "io/vtx_control.h"
|
||||
#include "io/vtx.h"
|
||||
#include "io/vtx_string.h"
|
||||
|
||||
#include "msp/msp_box.h"
|
||||
#include "msp/msp_protocol.h"
|
||||
|
|
|
@ -20,6 +20,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#ifdef USE_VTX_TABLE
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
|
@ -33,6 +35,7 @@ typedef struct vtxTableConfig_s {
|
|||
char bandNames[VTX_TABLE_MAX_BANDS][VTX_TABLE_BAND_NAME_LENGTH + 1];
|
||||
char bandLetters[VTX_TABLE_MAX_BANDS];
|
||||
char channelNames[VTX_TABLE_MAX_CHANNELS][VTX_TABLE_CHANNEL_NAME_LENGTH + 1];
|
||||
bool isFactoryBand[VTX_TABLE_MAX_BANDS];
|
||||
|
||||
uint8_t powerLevels;
|
||||
uint16_t powerValues[VTX_TABLE_MAX_POWER_LEVELS];
|
||||
|
@ -41,3 +44,5 @@ typedef struct vtxTableConfig_s {
|
|||
|
||||
struct vtxTableConfig_s;
|
||||
PG_DECLARE(struct vtxTableConfig_s, vtxTableConfig);
|
||||
|
||||
#endif
|
||||
|
|
|
@ -557,25 +557,22 @@ static void convertVtxPower(spektrumVtx_t * vtx)
|
|||
{
|
||||
uint8_t const * powerIndexTable = NULL;
|
||||
|
||||
vtxCommonLookupPowerValue(vtxCommonDevice(), vtx->power, &vtx->powerValue);
|
||||
switch (vtxDeviceType) {
|
||||
|
||||
#if defined(USE_VTX_TRAMP)
|
||||
case VTXDEV_TRAMP:
|
||||
powerIndexTable = vtxTrampPi;
|
||||
vtx->powerValue = vtxCommonLookupPowerValue(vtxCommonDevice(), vtx->power - 1); // Lookup the device power value, 0-based table vs 1-based index. Doh.
|
||||
break;
|
||||
#endif
|
||||
#if defined(USE_VTX_SMARTAUDIO)
|
||||
case VTXDEV_SMARTAUDIO:
|
||||
powerIndexTable = vtxSaPi;
|
||||
vtx->powerValue = vtxCommonLookupPowerValue(vtxCommonDevice(), vtx->power - 1); // Lookup the device power value, 0-based table vs 1-based index. Doh.
|
||||
break;
|
||||
#endif
|
||||
#if defined(USE_VTX_RTC6705)
|
||||
case VTXDEV_RTC6705:
|
||||
powerIndexTable = vtxRTC6705Pi;
|
||||
// No power value table available.Hard code some "knowledge" here. Doh.
|
||||
vtx->powerValue = vtx->power == VTX_6705_POWER_200 ? 200 : 25;
|
||||
break;
|
||||
#endif
|
||||
|
||||
|
|
|
@ -382,8 +382,8 @@ vtx_unittest_SRC := \
|
|||
$(USER_DIR)/fc/rc_modes.c \
|
||||
$(USER_DIR)/fc/runtime_config.c \
|
||||
$(USER_DIR)/drivers/vtx_common.c \
|
||||
$(USER_DIR)/drivers/vtx_table.c \
|
||||
$(USER_DIR)/io/vtx_control.c \
|
||||
$(USER_DIR)/io/vtx_string.c \
|
||||
$(USER_DIR)/io/vtx.c \
|
||||
$(USER_DIR)/common/bitarray.c
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue