mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-14 20:10:18 +03:00
[SmartAudio] Added support for custom frequency tables (#8380)
[SmartAudio] Added support for custom frequency tables
This commit is contained in:
commit
ed266e7151
29 changed files with 516 additions and 591 deletions
|
@ -170,7 +170,6 @@ COMMON_SRC = \
|
||||||
telemetry/ibus.c \
|
telemetry/ibus.c \
|
||||||
telemetry/ibus_shared.c \
|
telemetry/ibus_shared.c \
|
||||||
sensors/esc_sensor.c \
|
sensors/esc_sensor.c \
|
||||||
io/vtx_string.c \
|
|
||||||
io/vtx.c \
|
io/vtx.c \
|
||||||
io/vtx_rtc6705.c \
|
io/vtx_rtc6705.c \
|
||||||
io/vtx_smartaudio.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_rtc6705.c \
|
||||||
cms/cms_menu_vtx_smartaudio.c \
|
cms/cms_menu_vtx_smartaudio.c \
|
||||||
cms/cms_menu_vtx_tramp.c \
|
cms/cms_menu_vtx_tramp.c \
|
||||||
io/vtx_string.c \
|
|
||||||
io/vtx.c \
|
io/vtx.c \
|
||||||
io/vtx_rtc6705.c \
|
io/vtx_rtc6705.c \
|
||||||
io/vtx_smartaudio.c \
|
io/vtx_smartaudio.c \
|
||||||
|
|
|
@ -2452,8 +2452,7 @@ static void cliVtx(char *cmdline)
|
||||||
ptr = nextArg(ptr);
|
ptr = nextArg(ptr);
|
||||||
if (ptr) {
|
if (ptr) {
|
||||||
val = atoi(ptr);
|
val = atoi(ptr);
|
||||||
// FIXME Use VTX API to get max
|
if (val >= 0 && val <= vtxTableBandCount) {
|
||||||
if (val >= 0 && val <= VTX_SETTINGS_MAX_BAND) {
|
|
||||||
cac->band = val;
|
cac->band = val;
|
||||||
validArgumentCount++;
|
validArgumentCount++;
|
||||||
}
|
}
|
||||||
|
@ -2461,8 +2460,7 @@ static void cliVtx(char *cmdline)
|
||||||
ptr = nextArg(ptr);
|
ptr = nextArg(ptr);
|
||||||
if (ptr) {
|
if (ptr) {
|
||||||
val = atoi(ptr);
|
val = atoi(ptr);
|
||||||
// FIXME Use VTX API to get max
|
if (val >= 0 && val <= vtxTableChannelCount) {
|
||||||
if (val >= 0 && val <= VTX_SETTINGS_MAX_CHANNEL) {
|
|
||||||
cac->channel = val;
|
cac->channel = val;
|
||||||
validArgumentCount++;
|
validArgumentCount++;
|
||||||
}
|
}
|
||||||
|
@ -2470,8 +2468,7 @@ static void cliVtx(char *cmdline)
|
||||||
ptr = nextArg(ptr);
|
ptr = nextArg(ptr);
|
||||||
if (ptr) {
|
if (ptr) {
|
||||||
val = atoi(ptr);
|
val = atoi(ptr);
|
||||||
// FIXME Use VTX API to get max
|
if (val >= 0 && val < vtxTablePowerLevels) {
|
||||||
if (val >= 0 && val < VTX_SETTINGS_POWER_COUNT) {
|
|
||||||
cac->power= val;
|
cac->power= val;
|
||||||
validArgumentCount++;
|
validArgumentCount++;
|
||||||
}
|
}
|
||||||
|
@ -2502,11 +2499,12 @@ static void cliVtx(char *cmdline)
|
||||||
|
|
||||||
#ifdef USE_VTX_TABLE
|
#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];
|
char freqtmp[5 + 1];
|
||||||
freqbuf[0] = 0;
|
freqbuf[0] = 0;
|
||||||
|
strcat(freqbuf, isFactory ? " FACTORY" : " CUSTOM ");
|
||||||
for (int channel = 0; channel < channels; channel++) {
|
for (int channel = 0; channel < channels; channel++) {
|
||||||
tfp_sprintf(freqtmp, " %4d", frequency[channel]);
|
tfp_sprintf(freqtmp, " %4d", frequency[channel]);
|
||||||
strcat(freqbuf, freqtmp);
|
strcat(freqbuf, freqtmp);
|
||||||
|
@ -2533,11 +2531,11 @@ static const char *printVtxTableBand(dumpFlags_t dumpMask, int band, const vtxTa
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
headingStr = cliPrintSectionHeading(dumpMask, !equalsDefault, headingStr);
|
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);
|
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);
|
cliDumpPrintLinef(dumpMask, equalsDefault, fmt, band + 1, currentConfig->bandNames[band], currentConfig->bandLetters[band], freqbuf);
|
||||||
return headingStr;
|
return headingStr;
|
||||||
}
|
}
|
||||||
|
@ -2822,8 +2820,20 @@ static void cliVtxTable(char *cmdline)
|
||||||
uint16_t bandfreq[VTX_TABLE_MAX_CHANNELS];
|
uint16_t bandfreq[VTX_TABLE_MAX_CHANNELS];
|
||||||
int channel = 0;
|
int channel = 0;
|
||||||
int channels = vtxTableConfigMutable()->channels;
|
int channels = vtxTableConfigMutable()->channels;
|
||||||
|
bool isFactory = false;
|
||||||
|
|
||||||
for (channel = 0; channel < channels && (tok = strtok_r(NULL, " ", &saveptr)); channel++) {
|
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);
|
int freq = atoi(tok);
|
||||||
if (freq < 0) {
|
if (freq < 0) {
|
||||||
cliPrintErrorLinef("INVALID FREQUENCY %s", tok);
|
cliPrintErrorLinef("INVALID FREQUENCY %s", tok);
|
||||||
|
@ -2846,6 +2856,7 @@ static void cliVtxTable(char *cmdline)
|
||||||
for (int i = 0; i < channel; i++) {
|
for (int i = 0; i < channel; i++) {
|
||||||
vtxTableConfigMutable()->frequency[band][i] = bandfreq[i];
|
vtxTableConfigMutable()->frequency[band][i] = bandfreq[i];
|
||||||
}
|
}
|
||||||
|
vtxTableConfigMutable()->isFactoryBand[band] = isFactory;
|
||||||
} else {
|
} else {
|
||||||
// Bad subcommand
|
// Bad subcommand
|
||||||
cliPrintErrorLinef("INVALID SUBCOMMAND %s", tok);
|
cliPrintErrorLinef("INVALID SUBCOMMAND %s", tok);
|
||||||
|
@ -6038,7 +6049,7 @@ const clicmd_t cmdTable[] = {
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_VTX_TABLE
|
#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
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -39,6 +39,7 @@
|
||||||
#include "drivers/light_led.h"
|
#include "drivers/light_led.h"
|
||||||
#include "drivers/pinio.h"
|
#include "drivers/pinio.h"
|
||||||
#include "drivers/vtx_common.h"
|
#include "drivers/vtx_common.h"
|
||||||
|
#include "drivers/vtx_table.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "fc/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
|
@ -1316,9 +1317,9 @@ const clivalue_t valueTable[] = {
|
||||||
|
|
||||||
// PG_VTX_CONFIG
|
// PG_VTX_CONFIG
|
||||||
#ifdef USE_VTX_COMMON
|
#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_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 = { VTX_SETTINGS_MIN_CHANNEL, VTX_SETTINGS_MAX_CHANNEL }, PG_VTX_SETTINGS_CONFIG, offsetof(vtxSettingsConfig_t, channel) },
|
{ "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 = { VTX_SETTINGS_MIN_POWER, VTX_SETTINGS_POWER_COUNT-1 }, PG_VTX_SETTINGS_CONFIG, offsetof(vtxSettingsConfig_t, power) },
|
{ "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) },
|
{ "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
|
#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) },
|
{ "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 <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <ctype.h>
|
#include <ctype.h>
|
||||||
|
#include <drivers/vtx_table.h>
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
@ -36,7 +37,6 @@
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "fc/config.h"
|
||||||
|
|
||||||
#include "io/vtx_string.h"
|
|
||||||
#include "io/vtx_rtc6705.h"
|
#include "io/vtx_rtc6705.h"
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
|
|
||||||
|
@ -45,23 +45,22 @@ static uint8_t cmsx_vtxChannel;
|
||||||
static uint8_t cmsx_vtxPower;
|
static uint8_t cmsx_vtxPower;
|
||||||
|
|
||||||
static OSD_TAB_t entryVtxBand;
|
static OSD_TAB_t entryVtxBand;
|
||||||
static OSD_UINT8_t entryVtxChannel;
|
static OSD_TAB_t entryVtxChannel;
|
||||||
static OSD_TAB_t entryVtxPower;
|
static OSD_TAB_t entryVtxPower;
|
||||||
|
|
||||||
static void cmsx_Vtx_ConfigRead(void)
|
static void cmsx_Vtx_ConfigRead(void)
|
||||||
{
|
{
|
||||||
cmsx_vtxBand = vtxSettingsConfig()->band - 1;
|
vtxCommonGetBandAndChannel(vtxCommonDevice(), &cmsx_vtxBand, &cmsx_vtxChannel);
|
||||||
cmsx_vtxChannel = vtxSettingsConfig()->channel;
|
vtxCommonGetPowerIndex(vtxCommonDevice(), &cmsx_vtxPower);
|
||||||
cmsx_vtxPower = vtxSettingsConfig()->power - VTX_RTC6705_MIN_POWER;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
static void cmsx_Vtx_ConfigWriteback(void)
|
static void cmsx_Vtx_ConfigWriteback(void)
|
||||||
{
|
{
|
||||||
// update vtx_ settings
|
// update vtx_ settings
|
||||||
vtxSettingsConfigMutable()->band = cmsx_vtxBand + 1;
|
vtxSettingsConfigMutable()->band = cmsx_vtxBand;
|
||||||
vtxSettingsConfigMutable()->channel = cmsx_vtxChannel;
|
vtxSettingsConfigMutable()->channel = cmsx_vtxChannel;
|
||||||
vtxSettingsConfigMutable()->power = cmsx_vtxPower + VTX_RTC6705_MIN_POWER;
|
vtxSettingsConfigMutable()->power = cmsx_vtxPower;
|
||||||
vtxSettingsConfigMutable()->freq = vtxCommonLookupFrequency(vtxCommonDevice(), cmsx_vtxBand + 1, cmsx_vtxChannel);
|
vtxSettingsConfigMutable()->freq = vtxCommonLookupFrequency(vtxCommonDevice(), cmsx_vtxBand, cmsx_vtxChannel);
|
||||||
|
|
||||||
saveConfigAndNotify();
|
saveConfigAndNotify();
|
||||||
}
|
}
|
||||||
|
@ -70,20 +69,17 @@ static long cmsx_Vtx_onEnter(void)
|
||||||
{
|
{
|
||||||
cmsx_Vtx_ConfigRead();
|
cmsx_Vtx_ConfigRead();
|
||||||
|
|
||||||
vtxDevice_t *device = vtxCommonDevice();
|
|
||||||
|
|
||||||
entryVtxBand.val = &cmsx_vtxBand;
|
entryVtxBand.val = &cmsx_vtxBand;
|
||||||
entryVtxBand.max = device->capability.bandCount - 1;
|
entryVtxBand.max = vtxTableBandCount;
|
||||||
entryVtxBand.names = &device->bandNames[1];
|
entryVtxBand.names = vtxTableBandNames;
|
||||||
|
|
||||||
entryVtxChannel.val = &cmsx_vtxChannel;
|
entryVtxChannel.val = &cmsx_vtxChannel;
|
||||||
entryVtxChannel.min = 1;
|
entryVtxChannel.max = vtxTableChannelCount;
|
||||||
entryVtxChannel.max = device->capability.channelCount;
|
entryVtxChannel.names = vtxTableChannelNames;
|
||||||
entryVtxChannel.step = 1;
|
|
||||||
|
|
||||||
entryVtxPower.val = &cmsx_vtxPower;
|
entryVtxPower.val = &cmsx_vtxPower;
|
||||||
entryVtxPower.max = device->capability.powerCount - 1;
|
entryVtxPower.max = vtxTablePowerLevels;
|
||||||
entryVtxPower.names = device->powerNames;
|
entryVtxPower.names = vtxTablePowerLabels;
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
@ -97,13 +93,41 @@ static long cmsx_Vtx_onExit(const OSD_Entry *self)
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static long cmsx_Vtx_onBandChange(displayPort_t *pDisp, const void *self)
|
||||||
static const OSD_Entry cmsx_menuVtxEntries[] =
|
|
||||||
{
|
{
|
||||||
|
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},
|
{"--- VTX ---", OME_Label, NULL, NULL, 0},
|
||||||
{"BAND", OME_TAB, NULL, &entryVtxBand, 0},
|
{"BAND", OME_TAB, cmsx_Vtx_onBandChange, &entryVtxBand, 0},
|
||||||
{"CHANNEL", OME_UINT8, NULL, &entryVtxChannel, 0},
|
{"CHANNEL", OME_TAB, cmsx_Vtx_onChanChange, &entryVtxChannel, 0},
|
||||||
{"POWER", OME_TAB, NULL, &entryVtxPower, 0},
|
{"POWER", OME_TAB, cmsx_Vtx_onPowerChange, &entryVtxPower, 0},
|
||||||
{"BACK", OME_Back, NULL, NULL, 0},
|
{"BACK", OME_Back, NULL, NULL, 0},
|
||||||
{NULL, OME_END, NULL, NULL, 0}
|
{NULL, OME_END, NULL, NULL, 0}
|
||||||
};
|
};
|
||||||
|
@ -114,7 +138,7 @@ CMS_Menu cmsx_menuVtxRTC6705 = {
|
||||||
.GUARD_type = OME_MENU,
|
.GUARD_type = OME_MENU,
|
||||||
#endif
|
#endif
|
||||||
.onEnter = cmsx_Vtx_onEnter,
|
.onEnter = cmsx_Vtx_onEnter,
|
||||||
.onExit= cmsx_Vtx_onExit,
|
.onExit = cmsx_Vtx_onExit,
|
||||||
.entries = cmsx_menuVtxEntries
|
.entries = cmsx_menuVtxEntries
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -22,6 +22,7 @@
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <ctype.h>
|
#include <ctype.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
#include <drivers/vtx_table.h>
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
@ -38,7 +39,6 @@
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "fc/config.h"
|
||||||
|
|
||||||
#include "io/vtx_string.h"
|
|
||||||
#include "io/vtx_smartaudio.h"
|
#include "io/vtx_smartaudio.h"
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
|
|
||||||
|
@ -89,7 +89,7 @@ void saCmsUpdate(void)
|
||||||
// This is a first valid response to GET_SETTINGS.
|
// This is a first valid response to GET_SETTINGS.
|
||||||
saCmsOpmodel = saDevice.willBootIntoPitMode ? SACMS_OPMODEL_RACE : SACMS_OPMODEL_FREE;
|
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;
|
saCmsBand = vtxSettingsConfig()->band;
|
||||||
saCmsChan = vtxSettingsConfig()->channel;
|
saCmsChan = vtxSettingsConfig()->channel;
|
||||||
|
@ -134,41 +134,45 @@ void saUpdateStatusString(void)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
// XXX These should be done somewhere else
|
// XXX These should be done somewhere else
|
||||||
if (saCmsDeviceStatus == 0 && saDevice.version != 0)
|
if (saCmsDeviceStatus == 0 && saDevice.version != 0)
|
||||||
saCmsDeviceStatus = saDevice.version;
|
saCmsDeviceStatus = saDevice.version;
|
||||||
if (saCmsORFreq == 0 && saDevice.orfreq != 0)
|
if (saCmsORFreq == 0 && saDevice.orfreq != 0)
|
||||||
saCmsORFreq = saDevice.orfreq;
|
saCmsORFreq = saDevice.orfreq;
|
||||||
if (saCmsUserFreq == 0 && saDevice.freq != 0)
|
if (saCmsUserFreq == 0 && saDevice.freq != 0)
|
||||||
saCmsUserFreq = saDevice.freq;
|
saCmsUserFreq = saDevice.freq;
|
||||||
|
|
||||||
if (saDevice.version == 2) {
|
if (saDevice.version == 2) {
|
||||||
if (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE)
|
if (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE)
|
||||||
saCmsPitFMode = 1;
|
saCmsPitFMode = 1;
|
||||||
else
|
else
|
||||||
saCmsPitFMode = 0;
|
saCmsPitFMode = 0;
|
||||||
} else if (saDevice.version == 3) {
|
} else if (saDevice.version == 3) {
|
||||||
saCmsPitFMode = 1;//V2.1 only supports PIR
|
saCmsPitFMode = 1;//V2.1 only supports PIR
|
||||||
}
|
}
|
||||||
|
|
||||||
const vtxDevice_t *device = vtxCommonDevice();
|
const vtxDevice_t *device = vtxCommonDevice();
|
||||||
|
|
||||||
saCmsStatusString[0] = "-FR"[saCmsOpmodel];
|
saCmsStatusString[0] = "-FR"[saCmsOpmodel];
|
||||||
|
|
||||||
if (saCmsFselMode == 0) {
|
if (saCmsFselMode == 0) {
|
||||||
saCmsStatusString[2] = vtxCommonLookupBandLetter(device, saDevice.channel / 8 + 1);
|
uint8_t band;
|
||||||
saCmsStatusString[3] = vtxCommonLookupChannelName(device, (saDevice.channel % 8) + 1)[0];
|
uint8_t channel;
|
||||||
|
vtxCommonGetBandAndChannel(device, &band, &channel);
|
||||||
|
saCmsStatusString[2] = vtxCommonLookupBandLetter(device, band);
|
||||||
|
saCmsStatusString[3] = vtxCommonLookupChannelName(device, channel)[0];
|
||||||
} else {
|
} else {
|
||||||
saCmsStatusString[2] = 'U';
|
saCmsStatusString[2] = 'U';
|
||||||
saCmsStatusString[3] = 'F';
|
saCmsStatusString[3] = 'F';
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((saDevice.mode & SA_MODE_GET_PITMODE)
|
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);
|
tfp_sprintf(&saCmsStatusString[5], "%4d", saDevice.orfreq);
|
||||||
else if (saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ)
|
} else {
|
||||||
tfp_sprintf(&saCmsStatusString[5], "%4d", saDevice.freq);
|
uint16_t freq = 0;
|
||||||
else
|
vtxCommonGetFrequency(device, &freq);
|
||||||
tfp_sprintf(&saCmsStatusString[5], "%4d", vtxCommonLookupFrequency(vtxCommonDevice(), saDevice.channel / 8 + 1, saDevice.channel % 8 + 1));
|
tfp_sprintf(&saCmsStatusString[5], "%4d", freq);
|
||||||
|
}
|
||||||
|
|
||||||
saCmsStatusString[9] = ' ';
|
saCmsStatusString[9] = ' ';
|
||||||
|
|
||||||
|
@ -185,14 +189,13 @@ if (saDevice.version == 2) {
|
||||||
} else {
|
} else {
|
||||||
saCmsPit = 1;
|
saCmsPit = 1;
|
||||||
uint8_t powerIndex = 0;
|
uint8_t powerIndex = 0;
|
||||||
bool powerFound = vtxCommonGetPowerIndex(vtxCommonDevice(), &powerIndex);
|
bool powerFound = vtxCommonGetPowerIndex(device, &powerIndex);
|
||||||
tfp_sprintf(&saCmsStatusString[10], "%s", powerFound ? vtxCommonLookupPowerName(vtxCommonDevice(), 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));
|
strncpy(saCmsStatusString, "PLEASE CONFIGURE VTXTABLE", sizeof(saCmsStatusString));
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void saCmsResetOpmodel()
|
void saCmsResetOpmodel()
|
||||||
|
@ -218,8 +221,9 @@ static long saCmsConfigBandByGvar(displayPort_t *pDisp, const void *self)
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred)
|
if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred) {
|
||||||
saSetBandAndChannel(saCmsBand - 1, saCmsChan - 1);
|
vtxCommonSetBandAndChannel(vtxCommonDevice(), saCmsBand, saCmsChan);
|
||||||
|
}
|
||||||
|
|
||||||
saCmsFreqRef = vtxCommonLookupFrequency(vtxCommonDevice(), saCmsBand, saCmsChan);
|
saCmsFreqRef = vtxCommonLookupFrequency(vtxCommonDevice(), saCmsBand, saCmsChan);
|
||||||
|
|
||||||
|
@ -243,10 +247,11 @@ static long saCmsConfigChanByGvar(displayPort_t *pDisp, const void *self)
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred)
|
if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred) {
|
||||||
saSetBandAndChannel(saCmsBand - 1, saCmsChan - 1);
|
vtxCommonSetBandAndChannel(vtxCommonDevice(), saCmsBand, saCmsChan);
|
||||||
|
}
|
||||||
|
|
||||||
saCmsFreqRef = vtxCommonLookupFrequency(vtxCommonDevice(), saCmsBand , saCmsChan);
|
saCmsFreqRef = vtxCommonLookupFrequency(vtxCommonDevice(), saCmsBand, saCmsChan);
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
@ -365,7 +370,7 @@ static long saCmsConfigOpmodelByGvar(displayPort_t *pDisp, const void *self)
|
||||||
// out-range receivers from getting blinded.
|
// out-range receivers from getting blinded.
|
||||||
saCmsPitFMode = 0;
|
saCmsPitFMode = 0;
|
||||||
saCmsConfigPitFModeByGvar(pDisp, self);
|
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));
|
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)
|
static void saCmsInitNames(void)
|
||||||
{
|
{
|
||||||
vtxDevice_t *device = vtxCommonDevice();
|
|
||||||
|
|
||||||
saCmsEntBand.val = &saCmsBand;
|
saCmsEntBand.val = &saCmsBand;
|
||||||
saCmsEntBand.max = device->capability.bandCount;
|
saCmsEntBand.max = vtxTableBandCount;
|
||||||
saCmsEntBand.names = device->bandNames;
|
saCmsEntBand.names = vtxTableBandNames;
|
||||||
|
|
||||||
saCmsEntChan.val = &saCmsChan;
|
saCmsEntChan.val = &saCmsChan;
|
||||||
saCmsEntChan.max = device->capability.channelCount;
|
saCmsEntChan.max = vtxTableChannelCount;
|
||||||
saCmsEntChan.names = device->channelNames;
|
saCmsEntChan.names = vtxTableChannelNames;
|
||||||
|
|
||||||
saCmsEntPower.val = &saCmsPower;
|
saCmsEntPower.val = &saCmsPower;
|
||||||
saCmsEntPower.max = device->capability.powerCount;
|
saCmsEntPower.max = vtxTablePowerLevels;
|
||||||
saCmsEntPower.names = device->powerNames;
|
saCmsEntPower.names = vtxTablePowerLabels;
|
||||||
}
|
}
|
||||||
|
|
||||||
static OSD_UINT16_t saCmsEntFreqRef = { &saCmsFreqRef, 5600, 5900, 0 };
|
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 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
|
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);
|
vtxCommonSetPitMode(vtxCommonDevice(), saCmsPit == 2);
|
||||||
}
|
}
|
||||||
newSettings.power = saCmsPower;
|
newSettings.power = saCmsPower;
|
||||||
|
|
|
@ -22,6 +22,7 @@
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <ctype.h>
|
#include <ctype.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
#include <drivers/vtx_table.h>
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
@ -37,7 +38,6 @@
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "fc/config.h"
|
||||||
|
|
||||||
#include "io/vtx_string.h"
|
|
||||||
#include "io/vtx_tramp.h"
|
#include "io/vtx_tramp.h"
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
|
|
||||||
|
@ -49,17 +49,22 @@ void trampCmsUpdateStatusString(void)
|
||||||
{
|
{
|
||||||
vtxDevice_t *vtxDevice = vtxCommonDevice();
|
vtxDevice_t *vtxDevice = vtxCommonDevice();
|
||||||
|
|
||||||
#if defined(USE_VTX_TABLE)
|
if (vtxTableBandCount == 0 || vtxTablePowerLevels == 0) {
|
||||||
if (vtxDevice->capability.bandCount == 0 || vtxDevice->capability.powerCount == 0) {
|
|
||||||
strncpy(trampCmsStatusString, "PLEASE CONFIGURE VTXTABLE", sizeof(trampCmsStatusString));
|
strncpy(trampCmsStatusString, "PLEASE CONFIGURE VTXTABLE", sizeof(trampCmsStatusString));
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
trampCmsStatusString[0] = '*';
|
trampCmsStatusString[0] = '*';
|
||||||
trampCmsStatusString[1] = ' ';
|
trampCmsStatusString[1] = ' ';
|
||||||
trampCmsStatusString[2] = vtxCommonLookupBandLetter(vtxDevice, trampBand);
|
uint8_t band;
|
||||||
trampCmsStatusString[3] = vtxCommonLookupChannelName(vtxDevice, trampChannel)[0];
|
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] = ' ';
|
trampCmsStatusString[4] = ' ';
|
||||||
|
|
||||||
if (trampCurFreq)
|
if (trampCurFreq)
|
||||||
|
@ -69,9 +74,9 @@ void trampCmsUpdateStatusString(void)
|
||||||
|
|
||||||
if (trampPower) {
|
if (trampPower) {
|
||||||
tfp_sprintf(&trampCmsStatusString[9], " %c%3d", (trampPower == trampConfiguredPower) ? ' ' : '*', trampPower);
|
tfp_sprintf(&trampCmsStatusString[9], " %c%3d", (trampPower == trampConfiguredPower) ? ' ' : '*', trampPower);
|
||||||
}
|
} else {
|
||||||
else
|
|
||||||
tfp_sprintf(&trampCmsStatusString[9], " ----");
|
tfp_sprintf(&trampCmsStatusString[9], " ----");
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t trampCmsPitMode = 0;
|
uint8_t trampCmsPitMode = 0;
|
||||||
|
@ -189,8 +194,7 @@ static bool trampCmsInitSettings(void)
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (trampBand > 0) trampCmsBand = trampBand;
|
vtxCommonGetBandAndChannel(device, &trampCmsBand, &trampCmsChan);
|
||||||
if (trampChannel > 0) trampCmsChan = trampChannel;
|
|
||||||
|
|
||||||
trampCmsUpdateFreqRef();
|
trampCmsUpdateFreqRef();
|
||||||
trampCmsPitMode = trampPitMode + 1;
|
trampCmsPitMode = trampPitMode + 1;
|
||||||
|
@ -202,16 +206,16 @@ static bool trampCmsInitSettings(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
trampCmsEntBand.val = &trampCmsBand;
|
trampCmsEntBand.val = &trampCmsBand;
|
||||||
trampCmsEntBand.max = device->capability.bandCount;
|
trampCmsEntBand.max = vtxTableBandCount;
|
||||||
trampCmsEntBand.names = device->bandNames;
|
trampCmsEntBand.names = vtxTableBandNames;
|
||||||
|
|
||||||
trampCmsEntChan.val = &trampCmsChan;
|
trampCmsEntChan.val = &trampCmsChan;
|
||||||
trampCmsEntChan.max = device->capability.channelCount;
|
trampCmsEntChan.max = vtxTableChannelCount;
|
||||||
trampCmsEntChan.names = device->channelNames;
|
trampCmsEntChan.names = vtxTableChannelNames;
|
||||||
|
|
||||||
trampCmsEntPower.val = &trampCmsPower;
|
trampCmsEntPower.val = &trampCmsPower;
|
||||||
trampCmsEntPower.max = device->capability.powerCount;
|
trampCmsEntPower.max = vtxTablePowerLevels;
|
||||||
trampCmsEntPower.names = device->powerNames;
|
trampCmsEntPower.names = vtxTablePowerLabels;
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
|
@ -31,9 +31,12 @@
|
||||||
|
|
||||||
#include "common/time.h"
|
#include "common/time.h"
|
||||||
#include "drivers/vtx_common.h"
|
#include "drivers/vtx_common.h"
|
||||||
|
#include "drivers/vtx_table.h"
|
||||||
|
|
||||||
|
|
||||||
static vtxDevice_t *vtxDevice = NULL;
|
static vtxDevice_t *vtxDevice = NULL;
|
||||||
|
static uint8_t selectedBand = 0;
|
||||||
|
static uint8_t selectedChannel = 0;
|
||||||
|
|
||||||
void vtxCommonInit(void)
|
void vtxCommonInit(void)
|
||||||
{
|
{
|
||||||
|
@ -76,15 +79,22 @@ void vtxCommonProcess(vtxDevice_t *vtxDevice, timeUs_t currentTimeUs)
|
||||||
// band and channel are 1 origin
|
// band and channel are 1 origin
|
||||||
void vtxCommonSetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channel)
|
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);
|
||||||
vtxDevice->vTable->setBandAndChannel(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)
|
void vtxCommonSetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index)
|
||||||
{
|
{
|
||||||
if (index <= vtxDevice->capability.powerCount) {
|
if (index <= vtxTablePowerLevels) {
|
||||||
vtxDevice->vTable->setPowerByIndex(vtxDevice, index);
|
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)
|
void vtxCommonSetFrequency(vtxDevice_t *vtxDevice, uint16_t frequency)
|
||||||
{
|
{
|
||||||
|
selectedBand = 0;
|
||||||
|
selectedChannel = 0;
|
||||||
vtxDevice->vTable->setFrequency(vtxDevice, frequency);
|
vtxDevice->vTable->setFrequency(vtxDevice, frequency);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool vtxCommonGetBandAndChannel(const vtxDevice_t *vtxDevice, uint8_t *pBand, uint8_t *pChannel)
|
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)
|
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);
|
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)
|
const char *vtxCommonLookupBandName(const vtxDevice_t *vtxDevice, int band)
|
||||||
{
|
{
|
||||||
if (vtxDevice) {
|
if (vtxDevice) {
|
||||||
return vtxDevice->bandNames[band];
|
return vtxTableBandNames[band];
|
||||||
} else {
|
} else {
|
||||||
return "?";
|
return "?";
|
||||||
}
|
}
|
||||||
|
@ -138,7 +158,7 @@ const char *vtxCommonLookupBandName(const vtxDevice_t *vtxDevice, int band)
|
||||||
char vtxCommonLookupBandLetter(const vtxDevice_t *vtxDevice, int band)
|
char vtxCommonLookupBandLetter(const vtxDevice_t *vtxDevice, int band)
|
||||||
{
|
{
|
||||||
if (vtxDevice) {
|
if (vtxDevice) {
|
||||||
return vtxDevice->bandLetters[band];
|
return vtxTableBandLetters[band];
|
||||||
} else {
|
} else {
|
||||||
return '?';
|
return '?';
|
||||||
}
|
}
|
||||||
|
@ -147,25 +167,21 @@ char vtxCommonLookupBandLetter(const vtxDevice_t *vtxDevice, int band)
|
||||||
const char *vtxCommonLookupChannelName(const vtxDevice_t *vtxDevice, int channel)
|
const char *vtxCommonLookupChannelName(const vtxDevice_t *vtxDevice, int channel)
|
||||||
{
|
{
|
||||||
if (vtxDevice) {
|
if (vtxDevice) {
|
||||||
return vtxDevice->channelNames[channel];
|
return vtxTableChannelNames[channel];
|
||||||
} else {
|
} else {
|
||||||
return "?";
|
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.
|
//Converts frequency (in MHz) to band and channel values.
|
||||||
bool vtxCommonLookupBandChan(const vtxDevice_t *vtxDevice, uint16_t freq, uint8_t *pBand, uint8_t *pChannel)
|
bool vtxCommonLookupBandChan(const vtxDevice_t *vtxDevice, uint16_t freq, uint8_t *pBand, uint8_t *pChannel)
|
||||||
{
|
{
|
||||||
if (vtxDevice) {
|
if (vtxDevice) {
|
||||||
// Use reverse lookup order so that 5880Mhz
|
// Use reverse lookup order so that 5880Mhz
|
||||||
// get Raceband 7 instead of Fatshark 8.
|
// get Raceband 7 instead of Fatshark 8.
|
||||||
for (int band = vtxDevice->capability.bandCount - 1 ; band >= 0 ; band--) {
|
for (int band = vtxTableBandCount - 1 ; band >= 0 ; band--) {
|
||||||
for (int channel = 0 ; channel < vtxDevice->capability.channelCount ; channel++) {
|
for (int channel = 0 ; channel < vtxTableChannelCount ; channel++) {
|
||||||
if (vtxDevice->frequencyTable[band * VTX_SETTINGS_MAX_CHANNEL + channel] == freq) {
|
if (vtxTableFrequency[band][channel] == freq) {
|
||||||
*pBand = band + 1;
|
*pBand = band + 1;
|
||||||
*pChannel = channel + 1;
|
*pChannel = channel + 1;
|
||||||
return true;
|
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)
|
uint16_t vtxCommonLookupFrequency(const vtxDevice_t *vtxDevice, int band, int channel)
|
||||||
{
|
{
|
||||||
if (vtxDevice) {
|
if (vtxDevice) {
|
||||||
if (band > 0 && band <= vtxDevice->capability.bandCount &&
|
if (band > 0 && band <= vtxTableBandCount &&
|
||||||
channel > 0 && channel <= vtxDevice->capability.channelCount) {
|
channel > 0 && channel <= vtxTableChannelCount) {
|
||||||
return vtxDevice->frequencyTable[(band - 1) * VTX_SETTINGS_MAX_CHANNEL + (channel - 1)];
|
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)
|
const char *vtxCommonLookupPowerName(const vtxDevice_t *vtxDevice, int index)
|
||||||
{
|
{
|
||||||
if (vtxDevice) {
|
if (vtxDevice) {
|
||||||
return vtxDevice->powerNames[index];
|
return vtxTablePowerLabels[index];
|
||||||
} else {
|
} else {
|
||||||
return "?";
|
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) {
|
if (vtxDevice && index > 0 && index <= vtxTablePowerLevels) {
|
||||||
return vtxDevice->powerValues[index - 1];
|
*pPowerValue = vtxTablePowerValues[index - 1];
|
||||||
|
return true;
|
||||||
} else {
|
} else {
|
||||||
return 0;
|
return false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -27,20 +27,6 @@
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
#include "common/time.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
|
#define VTX_SETTINGS_MAX_FREQUENCY_MHZ 5999 //max freq (in MHz) for 'vtx_freq' setting
|
||||||
|
|
||||||
#if defined(USE_VTX_RTC6705)
|
#if defined(USE_VTX_RTC6705)
|
||||||
|
@ -51,19 +37,8 @@
|
||||||
|
|
||||||
#if defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP)
|
#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
|
#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
|
#endif
|
||||||
|
|
||||||
// check value for MSP_SET_VTX_CONFIG to determine if value is encoded
|
// check value for MSP_SET_VTX_CONFIG to determine if value is encoded
|
||||||
|
@ -79,7 +54,7 @@ typedef enum {
|
||||||
VTXDEV_UNKNOWN = 0xFF,
|
VTXDEV_UNKNOWN = 0xFF,
|
||||||
} vtxDevType_e;
|
} vtxDevType_e;
|
||||||
|
|
||||||
// VTX magic numbers
|
// VTX magic numbers used for spektrum vtx control
|
||||||
#define VTX_COMMON_BAND_USER 0
|
#define VTX_COMMON_BAND_USER 0
|
||||||
#define VTX_COMMON_BAND_A 1
|
#define VTX_COMMON_BAND_A 1
|
||||||
#define VTX_COMMON_BAND_B 2
|
#define VTX_COMMON_BAND_B 2
|
||||||
|
@ -88,51 +63,28 @@ typedef enum {
|
||||||
#define VTX_COMMON_BAND_RACE 5
|
#define VTX_COMMON_BAND_RACE 5
|
||||||
|
|
||||||
// RTC6705 RF Power index "---", 25 or 200 mW
|
// RTC6705 RF Power index "---", 25 or 200 mW
|
||||||
#define VTX_6705_POWER_OFF 0
|
#define VTX_6705_POWER_OFF 1
|
||||||
#define VTX_6705_POWER_25 1
|
#define VTX_6705_POWER_25 2
|
||||||
#define VTX_6705_POWER_200 2
|
#define VTX_6705_POWER_200 3
|
||||||
|
|
||||||
// SmartAudio "---", 25, 200, 500, 800 mW
|
// 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_25 1
|
||||||
#define VTX_SA_POWER_200 2
|
#define VTX_SA_POWER_200 2
|
||||||
#define VTX_SA_POWER_500 3
|
#define VTX_SA_POWER_500 3
|
||||||
#define VTX_SA_POWER_800 4
|
#define VTX_SA_POWER_800 4
|
||||||
|
|
||||||
// Tramp "---", 25, 100, 200, 400, 600 mW
|
// 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_25 1
|
||||||
#define VTX_TRAMP_POWER_100 2
|
#define VTX_TRAMP_POWER_100 2
|
||||||
#define VTX_TRAMP_POWER_200 3
|
#define VTX_TRAMP_POWER_200 3
|
||||||
#define VTX_TRAMP_POWER_400 4
|
#define VTX_TRAMP_POWER_400 4
|
||||||
#define VTX_TRAMP_POWER_600 5
|
#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;
|
struct vtxVTable_s;
|
||||||
typedef struct vtxDevice_s {
|
typedef struct vtxDevice_s {
|
||||||
const struct vtxVTable_s * const vTable;
|
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
|
|
||||||
} vtxDevice_t;
|
} 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 vtxCommonGetPowerIndex(const vtxDevice_t *vtxDevice, uint8_t *pIndex);
|
||||||
bool vtxCommonGetPitMode(const vtxDevice_t *vtxDevice, uint8_t *pOnOff);
|
bool vtxCommonGetPitMode(const vtxDevice_t *vtxDevice, uint8_t *pOnOff);
|
||||||
bool vtxCommonGetFrequency(const vtxDevice_t *vtxDevice, uint16_t *pFreq);
|
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);
|
const char *vtxCommonLookupBandName(const vtxDevice_t *vtxDevice, int band);
|
||||||
char vtxCommonLookupBandLetter(const vtxDevice_t *vtxDevice, int band);
|
char vtxCommonLookupBandLetter(const vtxDevice_t *vtxDevice, int band);
|
||||||
char vtxCommonGetBandLetter(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);
|
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);
|
bool vtxCommonLookupBandChan(const vtxDevice_t *vtxDevice, uint16_t freq, uint8_t *pBand, uint8_t *pChannel);
|
||||||
const char *vtxCommonLookupPowerName(const vtxDevice_t *vtxDevice, int index);
|
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)
|
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);
|
spiSetDivisor(busdev->busdev_u.spi.instance, SPI_CLOCK_SLOW);
|
||||||
|
|
||||||
|
|
|
@ -31,15 +31,13 @@
|
||||||
|
|
||||||
#include "pg/vtx_io.h"
|
#include "pg/vtx_io.h"
|
||||||
|
|
||||||
#define VTX_RTC6705_BAND_COUNT 5
|
#define VTX_RTC6705_POWER_COUNT 3
|
||||||
#define VTX_RTC6705_CHANNEL_COUNT 8
|
#define VTX_RTC6705_DEFAULT_POWER_INDEX 2
|
||||||
#define VTX_RTC6705_POWER_COUNT 3
|
|
||||||
#define VTX_RTC6705_DEFAULT_POWER 1
|
|
||||||
|
|
||||||
#if defined(RTC6705_POWER_PIN)
|
#if defined(RTC6705_POWER_PIN)
|
||||||
#define VTX_RTC6705_MIN_POWER 0
|
#define VTX_RTC6705_MIN_POWER_VALUE 0
|
||||||
#else
|
#else
|
||||||
#define VTX_RTC6705_MIN_POWER 1
|
#define VTX_RTC6705_MIN_POWER_VALUE 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define VTX_RTC6705_FREQ_MIN 5600
|
#define VTX_RTC6705_FREQ_MIN 5600
|
||||||
|
|
|
@ -27,27 +27,61 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#if defined(USE_VTX_TABLE)
|
#include "drivers/vtx_table.h"
|
||||||
|
|
||||||
|
#if defined(USE_VTX_TABLE)
|
||||||
#include "common/printf.h"
|
#include "common/printf.h"
|
||||||
|
|
||||||
#include "pg/vtx_table.h"
|
#include "pg/vtx_table.h"
|
||||||
#include "drivers/vtx_common.h"
|
#include "drivers/vtx_common.h"
|
||||||
#include "drivers/vtx_table.h"
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
#if defined(USE_VTX_TABLE)
|
||||||
int vtxTableBandCount;
|
int vtxTableBandCount;
|
||||||
int vtxTableChannelCount;
|
int vtxTableChannelCount;
|
||||||
uint16_t vtxTableFrequency[VTX_TABLE_MAX_BANDS][VTX_TABLE_MAX_CHANNELS];
|
uint16_t vtxTableFrequency[VTX_TABLE_MAX_BANDS][VTX_TABLE_MAX_CHANNELS];
|
||||||
const char * vtxTableBandNames[VTX_TABLE_MAX_BANDS + 1];
|
const char * vtxTableBandNames[VTX_TABLE_MAX_BANDS + 1];
|
||||||
char vtxTableBandLetters[VTX_TABLE_MAX_BANDS + 1];
|
char vtxTableBandLetters[VTX_TABLE_MAX_BANDS + 1];
|
||||||
const char * vtxTableChannelNames[VTX_TABLE_MAX_CHANNELS + 1];
|
const char * vtxTableChannelNames[VTX_TABLE_MAX_CHANNELS + 1];
|
||||||
|
bool vtxTableIsFactoryBand[VTX_TABLE_MAX_BANDS];
|
||||||
|
|
||||||
int vtxTablePowerLevels;
|
int vtxTablePowerLevels;
|
||||||
uint16_t vtxTablePowerValues[VTX_TABLE_MAX_POWER_LEVELS];
|
uint16_t vtxTablePowerValues[VTX_TABLE_MAX_POWER_LEVELS];
|
||||||
const char * vtxTablePowerLabels[VTX_TABLE_MAX_POWER_LEVELS + 1];
|
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)
|
void vtxTableInit(void)
|
||||||
{
|
{
|
||||||
|
#if defined(USE_VTX_TABLE)
|
||||||
const vtxTableConfig_t *config = vtxTableConfig();
|
const vtxTableConfig_t *config = vtxTableConfig();
|
||||||
|
|
||||||
vtxTableBandCount = config->bands;
|
vtxTableBandCount = config->bands;
|
||||||
|
@ -59,6 +93,7 @@ void vtxTableInit(void)
|
||||||
}
|
}
|
||||||
vtxTableBandNames[band + 1] = config->bandNames[band];
|
vtxTableBandNames[band + 1] = config->bandNames[band];
|
||||||
vtxTableBandLetters[band + 1] = config->bandLetters[band];
|
vtxTableBandLetters[band + 1] = config->bandLetters[band];
|
||||||
|
vtxTableIsFactoryBand[band] = config->isFactoryBand[band];
|
||||||
}
|
}
|
||||||
|
|
||||||
vtxTableBandNames[0] = "--------";
|
vtxTableBandNames[0] = "--------";
|
||||||
|
@ -76,8 +111,30 @@ void vtxTableInit(void)
|
||||||
vtxTablePowerLabels[0] = "---";
|
vtxTablePowerLabels[0] = "---";
|
||||||
|
|
||||||
vtxTablePowerLevels = config->powerLevels;
|
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)
|
void vtxTableStrncpyWithPad(char *dst, const char *src, int length)
|
||||||
{
|
{
|
||||||
char c;
|
char c;
|
||||||
|
@ -118,6 +175,7 @@ void vtxTableConfigClearBand(vtxTableConfig_t *config, int band)
|
||||||
tfp_sprintf(tempbuf, "BAND%d", band + 1);
|
tfp_sprintf(tempbuf, "BAND%d", band + 1);
|
||||||
vtxTableStrncpyWithPad(config->bandNames[band], tempbuf, VTX_TABLE_BAND_NAME_LENGTH);
|
vtxTableStrncpyWithPad(config->bandNames[band], tempbuf, VTX_TABLE_BAND_NAME_LENGTH);
|
||||||
config->bandLetters[band] = '1' + band;
|
config->bandLetters[band] = '1' + band;
|
||||||
|
config->isFactoryBand[band] = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void vtxTableConfigClearPowerValues(vtxTableConfig_t *config, int start)
|
void vtxTableConfigClearPowerValues(vtxTableConfig_t *config, int start)
|
||||||
|
|
|
@ -26,12 +26,34 @@
|
||||||
|
|
||||||
#include "drivers/vtx_common.h"
|
#include "drivers/vtx_common.h"
|
||||||
|
|
||||||
|
#ifdef USE_VTX_TABLE
|
||||||
#define VTX_TABLE_MAX_BANDS 8 // Maximum number of bands
|
#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_CHANNELS 8 // Maximum number of channels per band
|
||||||
#define VTX_TABLE_MAX_POWER_LEVELS 8 // Maximum number of power levels
|
#define VTX_TABLE_MAX_POWER_LEVELS 8 // Maximum number of power levels
|
||||||
#define VTX_TABLE_CHANNEL_NAME_LENGTH 1
|
#define VTX_TABLE_CHANNEL_NAME_LENGTH 1
|
||||||
#define VTX_TABLE_BAND_NAME_LENGTH 8
|
#define VTX_TABLE_BAND_NAME_LENGTH 8
|
||||||
#define VTX_TABLE_POWER_LABEL_LENGTH 3
|
#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;
|
struct vtxTableConfig_s;
|
||||||
void vtxTableInit(void);
|
void vtxTableInit(void);
|
||||||
|
@ -40,13 +62,17 @@ void vtxTableConfigClearBand(struct vtxTableConfig_s *config, int band);
|
||||||
void vtxTableConfigClearPowerValues(struct vtxTableConfig_s *config, int start);
|
void vtxTableConfigClearPowerValues(struct vtxTableConfig_s *config, int start);
|
||||||
void vtxTableConfigClearPowerLabels(struct vtxTableConfig_s *config, int start);
|
void vtxTableConfigClearPowerLabels(struct vtxTableConfig_s *config, int start);
|
||||||
void vtxTableConfigClearChannels(struct vtxTableConfig_s *config, int band, int channels);
|
void vtxTableConfigClearChannels(struct vtxTableConfig_s *config, int band, int channels);
|
||||||
|
#ifndef USE_VTX_TABLE
|
||||||
|
void vtxTableSetFactoryBands(bool isFactory);
|
||||||
|
#endif
|
||||||
|
|
||||||
extern int vtxTableBandCount;
|
extern int vtxTableBandCount;
|
||||||
extern int vtxTableChannelCount;
|
extern int vtxTableChannelCount;
|
||||||
extern uint16_t vtxTableFrequency[VTX_TABLE_MAX_BANDS][VTX_TABLE_MAX_CHANNELS];
|
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 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 int vtxTablePowerLevels;
|
||||||
extern uint16_t vtxTablePowerValues[VTX_TABLE_MAX_POWER_LEVELS];
|
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);
|
baroSetCalibrationCycles(CALIBRATING_BARO_CYCLES);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_VTX_TABLE
|
#if defined(USE_VTX_COMMON) || defined(USE_VTX_CONTROL)
|
||||||
vtxTableInit();
|
vtxTableInit();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -65,7 +65,6 @@
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
#include "io/ledstrip.h"
|
#include "io/ledstrip.h"
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "io/vtx_string.h"
|
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
||||||
|
|
|
@ -26,7 +26,6 @@
|
||||||
#include "fc/config.h"
|
#include "fc/config.h"
|
||||||
#include "drivers/vtx_common.h"
|
#include "drivers/vtx_common.h"
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
#include "io/vtx_string.h"
|
|
||||||
|
|
||||||
#include "io/spektrum_vtx_control.h"
|
#include "io/spektrum_vtx_control.h"
|
||||||
|
|
||||||
|
|
|
@ -31,6 +31,7 @@
|
||||||
#include "common/time.h"
|
#include "common/time.h"
|
||||||
|
|
||||||
#include "drivers/vtx_common.h"
|
#include "drivers/vtx_common.h"
|
||||||
|
#include "drivers/vtx_table.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "fc/config.h"
|
||||||
#include "fc/rc_modes.h"
|
#include "fc/rc_modes.h"
|
||||||
|
@ -38,7 +39,6 @@
|
||||||
|
|
||||||
#include "flight/failsafe.h"
|
#include "flight/failsafe.h"
|
||||||
|
|
||||||
#include "io/vtx_string.h"
|
|
||||||
#include "io/vtx_control.h"
|
#include "io/vtx_control.h"
|
||||||
|
|
||||||
#include "pg/pg.h"
|
#include "pg/pg.h"
|
||||||
|
@ -50,13 +50,13 @@
|
||||||
PG_REGISTER_WITH_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig, PG_VTX_SETTINGS_CONFIG, 0);
|
PG_REGISTER_WITH_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig, PG_VTX_SETTINGS_CONFIG, 0);
|
||||||
|
|
||||||
PG_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig,
|
PG_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig,
|
||||||
.band = VTX_SETTINGS_DEFAULT_BAND,
|
.band = VTX_TABLE_DEFAULT_BAND,
|
||||||
.channel = VTX_SETTINGS_DEFAULT_CHANNEL,
|
.channel = VTX_TABLE_DEFAULT_CHANNEL,
|
||||||
.power = VTX_SETTINGS_DEFAULT_POWER,
|
.power = VTX_TABLE_DEFAULT_POWER,
|
||||||
.freq = VTX_SETTINGS_DEFAULT_FREQ,
|
.freq = VTX_TABLE_DEFAULT_FREQ,
|
||||||
.pitModeFreq = VTX_SETTINGS_DEFAULT_PITMODE_FREQ,
|
.pitModeFreq = VTX_TABLE_DEFAULT_PITMODE_FREQ,
|
||||||
.lowPowerDisarm = VTX_LOW_POWER_DISARM_OFF,
|
.lowPowerDisarm = VTX_LOW_POWER_DISARM_OFF,
|
||||||
);
|
);
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
VTX_PARAM_POWER = 0,
|
VTX_PARAM_POWER = 0,
|
||||||
|
@ -88,7 +88,7 @@ void vtxInit(void)
|
||||||
#if defined(VTX_SETTINGS_FREQCMD)
|
#if defined(VTX_SETTINGS_FREQCMD)
|
||||||
// constrain pit mode frequency
|
// constrain pit mode frequency
|
||||||
if (vtxSettingsConfig()->pitModeFreq) {
|
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) {
|
if (constrainedPitModeFreq != vtxSettingsConfig()->pitModeFreq) {
|
||||||
vtxSettingsConfigMutable()->pitModeFreq = constrainedPitModeFreq;
|
vtxSettingsConfigMutable()->pitModeFreq = constrainedPitModeFreq;
|
||||||
settingsUpdated = true;
|
settingsUpdated = true;
|
||||||
|
@ -116,14 +116,14 @@ STATIC_UNIT_TESTED vtxSettingsConfig_t vtxGetSettings(void)
|
||||||
if (IS_RC_MODE_ACTIVE(BOXVTXPITMODE) && settings.pitModeFreq) {
|
if (IS_RC_MODE_ACTIVE(BOXVTXPITMODE) && settings.pitModeFreq) {
|
||||||
settings.band = 0;
|
settings.band = 0;
|
||||||
settings.freq = settings.pitModeFreq;
|
settings.freq = settings.pitModeFreq;
|
||||||
settings.power = VTX_SETTINGS_DEFAULT_POWER;
|
settings.power = VTX_TABLE_DEFAULT_POWER;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (!ARMING_FLAG(ARMED) && !failsafeIsActive() &&
|
if (!ARMING_FLAG(ARMED) && !failsafeIsActive() &&
|
||||||
(settings.lowPowerDisarm == VTX_LOW_POWER_DISARM_ALWAYS ||
|
(settings.lowPowerDisarm == VTX_LOW_POWER_DISARM_ALWAYS ||
|
||||||
(settings.lowPowerDisarm == VTX_LOW_POWER_DISARM_UNTIL_FIRST_ARM && !ARMING_FLAG(WAS_EVER_ARMED)))) {
|
(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;
|
return settings;
|
||||||
|
@ -131,7 +131,7 @@ STATIC_UNIT_TESTED vtxSettingsConfig_t vtxGetSettings(void)
|
||||||
|
|
||||||
static bool vtxProcessBandAndChannel(vtxDevice_t *vtxDevice)
|
static bool vtxProcessBandAndChannel(vtxDevice_t *vtxDevice)
|
||||||
{
|
{
|
||||||
if(!ARMING_FLAG(ARMED)) {
|
if (!ARMING_FLAG(ARMED)) {
|
||||||
uint8_t vtxBand;
|
uint8_t vtxBand;
|
||||||
uint8_t vtxChan;
|
uint8_t vtxChan;
|
||||||
if (vtxCommonGetBandAndChannel(vtxDevice, &vtxBand, &vtxChan)) {
|
if (vtxCommonGetBandAndChannel(vtxDevice, &vtxBand, &vtxChan)) {
|
||||||
|
@ -148,7 +148,7 @@ static bool vtxProcessBandAndChannel(vtxDevice_t *vtxDevice)
|
||||||
#if defined(VTX_SETTINGS_FREQCMD)
|
#if defined(VTX_SETTINGS_FREQCMD)
|
||||||
static bool vtxProcessFrequency(vtxDevice_t *vtxDevice)
|
static bool vtxProcessFrequency(vtxDevice_t *vtxDevice)
|
||||||
{
|
{
|
||||||
if(!ARMING_FLAG(ARMED)) {
|
if (!ARMING_FLAG(ARMED)) {
|
||||||
uint16_t vtxFreq;
|
uint16_t vtxFreq;
|
||||||
if (vtxCommonGetFrequency(vtxDevice, &vtxFreq)) {
|
if (vtxCommonGetFrequency(vtxDevice, &vtxFreq)) {
|
||||||
const vtxSettingsConfig_t settings = vtxGetSettings();
|
const vtxSettingsConfig_t settings = vtxGetSettings();
|
||||||
|
|
|
@ -27,9 +27,9 @@
|
||||||
#include "pg/pg.h"
|
#include "pg/pg.h"
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
VTX_LOW_POWER_DISARM_OFF = 0,
|
VTX_LOW_POWER_DISARM_OFF = 0,
|
||||||
VTX_LOW_POWER_DISARM_ALWAYS,
|
VTX_LOW_POWER_DISARM_ALWAYS,
|
||||||
VTX_LOW_POWER_DISARM_UNTIL_FIRST_ARM, // Set low power until arming for the first time
|
VTX_LOW_POWER_DISARM_UNTIL_FIRST_ARM, // Set low power until arming for the first time
|
||||||
} vtxLowerPowerDisarm_e;
|
} vtxLowerPowerDisarm_e;
|
||||||
|
|
||||||
typedef struct vtxSettingsConfig_s {
|
typedef struct vtxSettingsConfig_s {
|
||||||
|
|
|
@ -20,6 +20,7 @@
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
#include <drivers/vtx_table.h>
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
@ -64,7 +65,7 @@ void vtxControlInit(void)
|
||||||
|
|
||||||
void vtxControlInputPoll(void)
|
void vtxControlInputPoll(void)
|
||||||
{
|
{
|
||||||
// Check variuos input sources for VTX config updates
|
// Check variuos input sources for VTX config updates
|
||||||
#if defined(USE_SPEKTRUM_VTX_CONTROL)
|
#if defined(USE_SPEKTRUM_VTX_CONTROL)
|
||||||
// Get VTX updates
|
// Get VTX updates
|
||||||
spektrumVtxControl();
|
spektrumVtxControl();
|
||||||
|
@ -142,25 +143,24 @@ void vtxCycleBandOrChannel(const uint8_t bandStep, const uint8_t channelStep)
|
||||||
const vtxDevice_t *vtxDevice = vtxCommonDevice();
|
const vtxDevice_t *vtxDevice = vtxCommonDevice();
|
||||||
if (vtxDevice) {
|
if (vtxDevice) {
|
||||||
uint8_t band = 0, channel = 0;
|
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) {
|
if (!haveAllNeededInfo) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
int newChannel = channel + channelStep;
|
int newChannel = channel + channelStep;
|
||||||
if (newChannel > capability.channelCount) {
|
if (newChannel > vtxTableChannelCount) {
|
||||||
newChannel = 1;
|
newChannel = 1;
|
||||||
} else if (newChannel < 1) {
|
} else if (newChannel < 1) {
|
||||||
newChannel = capability.channelCount;
|
newChannel = vtxTableChannelCount;
|
||||||
}
|
}
|
||||||
|
|
||||||
int newBand = band + bandStep;
|
int newBand = band + bandStep;
|
||||||
if (newBand > capability.bandCount) {
|
if (newBand > vtxTableBandCount) {
|
||||||
newBand = 1;
|
newBand = 1;
|
||||||
} else if (newBand < 1) {
|
} else if (newBand < 1) {
|
||||||
newBand = capability.bandCount;
|
newBand = vtxTableBandCount;
|
||||||
}
|
}
|
||||||
|
|
||||||
vtxSettingsConfigMutable()->band = newBand;
|
vtxSettingsConfigMutable()->band = newBand;
|
||||||
|
@ -173,17 +173,16 @@ void vtxCyclePower(const uint8_t powerStep)
|
||||||
const vtxDevice_t *vtxDevice = vtxCommonDevice();
|
const vtxDevice_t *vtxDevice = vtxCommonDevice();
|
||||||
if (vtxDevice) {
|
if (vtxDevice) {
|
||||||
uint8_t power = 0;
|
uint8_t power = 0;
|
||||||
vtxDeviceCapability_t capability;
|
const bool haveAllNeededInfo = vtxCommonGetPowerIndex(vtxDevice, &power);
|
||||||
const bool haveAllNeededInfo = vtxCommonGetPowerIndex(vtxDevice, &power) && vtxCommonGetDeviceCapability(vtxDevice, &capability);
|
|
||||||
if (!haveAllNeededInfo) {
|
if (!haveAllNeededInfo) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
int newPower = power + powerStep;
|
int newPower = power + powerStep;
|
||||||
if (newPower >= capability.powerCount) {
|
if (newPower >= vtxTablePowerLevels) {
|
||||||
newPower = 0;
|
newPower = 0;
|
||||||
} else if (newPower < 0) {
|
} else if (newPower < 0) {
|
||||||
newPower = capability.powerCount;
|
newPower = vtxTablePowerLevels;
|
||||||
}
|
}
|
||||||
|
|
||||||
vtxSettingsConfigMutable()->power = newPower;
|
vtxSettingsConfigMutable()->power = newPower;
|
||||||
|
|
|
@ -34,16 +34,16 @@
|
||||||
|
|
||||||
#include "drivers/max7456.h"
|
#include "drivers/max7456.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
#include "drivers/vtx_table.h"
|
||||||
#include "drivers/vtx_rtc6705.h"
|
#include "drivers/vtx_rtc6705.h"
|
||||||
|
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
#include "io/vtx_rtc6705.h"
|
#include "io/vtx_rtc6705.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 char * rtc6705PowerNames[] = {
|
const char *rtc6705PowerNames[VTX_RTC6705_POWER_COUNT + 1] = {
|
||||||
"OFF", "MIN", "MAX"
|
"---", "OFF", "MIN", "MAX"
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -54,21 +54,26 @@ static vtxDevice_t vtxRTC6705 = {
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
static uint16_t rtc6705Frequency;
|
||||||
|
static int8_t rtc6705PowerIndex;
|
||||||
|
|
||||||
static void vtxRTC6705SetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channel);
|
static void vtxRTC6705SetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channel);
|
||||||
static void vtxRTC6705SetFrequency(vtxDevice_t *vtxDevice, uint16_t frequency);
|
static void vtxRTC6705SetFrequency(vtxDevice_t *vtxDevice, uint16_t frequency);
|
||||||
|
|
||||||
bool vtxRTC6705Init(void)
|
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);
|
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();
|
vtxInit();
|
||||||
|
|
||||||
|
@ -88,8 +93,10 @@ bool vtxRTC6705CanUpdate(void)
|
||||||
#ifdef RTC6705_POWER_PIN
|
#ifdef RTC6705_POWER_PIN
|
||||||
static void vtxRTC6705Configure(vtxDevice_t *vtxDevice)
|
static void vtxRTC6705Configure(vtxDevice_t *vtxDevice)
|
||||||
{
|
{
|
||||||
rtc6705SetRFPower(vtxDevice->powerIndex);
|
uint16_t newPowerValue = 0;
|
||||||
vtxRTC6705SetBandAndChannel(vtxDevice, vtxDevice->band, vtxDevice->channel);
|
vtxCommonLookupPowerValue(vtxDevice, rtc6705PowerIndex, &newPowerValue);
|
||||||
|
rtc6705SetRFPower(newPowerValue);
|
||||||
|
vtxRTC6705SetFrequency(vtxDevice, rtc6705Frequency);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void vtxRTC6705EnableAndConfigure(vtxDevice_t *vtxDevice)
|
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)
|
static void vtxRTC6705SetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channel)
|
||||||
{
|
{
|
||||||
while (!vtxRTC6705CanUpdate());
|
UNUSED(vtxDevice);
|
||||||
|
UNUSED(band);
|
||||||
if (band >= 1 && band <= VTX_SETTINGS_BAND_COUNT && channel >= 1 && channel <= VTX_SETTINGS_CHANNEL_COUNT) {
|
UNUSED(channel);
|
||||||
if (vtxDevice->powerIndex > 0) {
|
//rtc6705 does not support bands and channels, only frequencies
|
||||||
vtxDevice->band = band;
|
|
||||||
vtxDevice->channel = channel;
|
|
||||||
vtxRTC6705SetFrequency(vtxDevice, vtxCommonLookupFrequency(vtxDevice, band, channel));
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
static void vtxRTC6705SetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index)
|
static void vtxRTC6705SetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index)
|
||||||
{
|
{
|
||||||
while (!vtxRTC6705CanUpdate());
|
while (!vtxRTC6705CanUpdate());
|
||||||
|
|
||||||
|
uint16_t newPowerValue = 0;
|
||||||
|
if (!vtxCommonLookupPowerValue(vtxDevice, index, &newPowerValue)) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
uint16_t currentPowerValue = 0;
|
||||||
|
vtxCommonLookupPowerValue(vtxDevice, rtc6705PowerIndex, ¤tPowerValue);
|
||||||
#ifdef RTC6705_POWER_PIN
|
#ifdef RTC6705_POWER_PIN
|
||||||
if (index == 0) {
|
if (newPowerValue == 0) {
|
||||||
// power device off
|
// power device off
|
||||||
if (vtxDevice->powerIndex > 0) {
|
if (currentPowerValue > 0) {
|
||||||
// on, power it off
|
// on, power it off
|
||||||
vtxDevice->powerIndex = index;
|
rtc6705PowerIndex = index;
|
||||||
rtc6705Disable();
|
rtc6705Disable();
|
||||||
return;
|
return;
|
||||||
} else {
|
} else {
|
||||||
|
@ -154,20 +162,20 @@ static void vtxRTC6705SetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index)
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
// change rf power and maybe turn the device on first
|
// 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.
|
// if it's powered down, power it up, wait and configure channel, band and power.
|
||||||
vtxDevice->powerIndex = index;
|
rtc6705PowerIndex = index;
|
||||||
vtxRTC6705EnableAndConfigure(vtxDevice);
|
vtxRTC6705EnableAndConfigure(vtxDevice);
|
||||||
return;
|
return;
|
||||||
} else {
|
} else {
|
||||||
// if it's powered up, just set the rf power
|
// if it's powered up, just set the rf power
|
||||||
vtxDevice->powerIndex = index;
|
rtc6705PowerIndex = index;
|
||||||
rtc6705SetRFPower(index);
|
rtc6705SetRFPower(newPowerValue);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
vtxDevice->powerIndex = MAX(index, VTX_RTC6705_MIN_POWER);
|
rtc6705PowerIndex = index;
|
||||||
rtc6705SetRFPower(index);
|
rtc6705SetRFPower(MAX(newPowerValue, VTX_RTC6705_MIN_POWER_VALUE);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -179,23 +187,28 @@ static void vtxRTC6705SetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff)
|
||||||
|
|
||||||
static void vtxRTC6705SetFrequency(vtxDevice_t *vtxDevice, uint16_t frequency)
|
static void vtxRTC6705SetFrequency(vtxDevice_t *vtxDevice, uint16_t frequency)
|
||||||
{
|
{
|
||||||
|
UNUSED(vtxDevice);
|
||||||
if (frequency >= VTX_RTC6705_FREQ_MIN && frequency <= VTX_RTC6705_FREQ_MAX) {
|
if (frequency >= VTX_RTC6705_FREQ_MIN && frequency <= VTX_RTC6705_FREQ_MAX) {
|
||||||
frequency = constrain(frequency, VTX_RTC6705_FREQ_MIN, VTX_RTC6705_FREQ_MAX);
|
frequency = constrain(frequency, VTX_RTC6705_FREQ_MIN, VTX_RTC6705_FREQ_MAX);
|
||||||
vtxDevice->frequency = frequency;
|
rtc6705Frequency = frequency;
|
||||||
rtc6705SetFrequency(frequency);
|
rtc6705SetFrequency(frequency);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool vtxRTC6705GetBandAndChannel(const vtxDevice_t *vtxDevice, uint8_t *pBand, uint8_t *pChannel)
|
static bool vtxRTC6705GetBandAndChannel(const vtxDevice_t *vtxDevice, uint8_t *pBand, uint8_t *pChannel)
|
||||||
{
|
{
|
||||||
*pBand = vtxDevice->band;
|
UNUSED(vtxDevice);
|
||||||
*pChannel = vtxDevice->channel;
|
*pBand = 0;
|
||||||
|
*pChannel = 0;
|
||||||
|
//rtc6705 does not support bands and channels, only frequencies.
|
||||||
|
//therefore always return 0
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool vtxRTC6705GetPowerIndex(const vtxDevice_t *vtxDevice, uint8_t *pIndex)
|
static bool vtxRTC6705GetPowerIndex(const vtxDevice_t *vtxDevice, uint8_t *pIndex)
|
||||||
{
|
{
|
||||||
*pIndex = vtxDevice->powerIndex;
|
UNUSED(vtxDevice);
|
||||||
|
*pIndex = rtc6705PowerIndex;
|
||||||
return true;
|
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)
|
static bool vtxRTC6705GetFreq(const vtxDevice_t *vtxDevice, uint16_t *pFrequency)
|
||||||
{
|
{
|
||||||
*pFrequency = vtxDevice->frequency;
|
UNUSED(vtxDevice);
|
||||||
|
*pFrequency = rtc6705Frequency;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -46,7 +46,6 @@
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
#include "io/vtx_control.h"
|
#include "io/vtx_control.h"
|
||||||
#include "io/vtx_smartaudio.h"
|
#include "io/vtx_smartaudio.h"
|
||||||
#include "io/vtx_string.h"
|
|
||||||
|
|
||||||
|
|
||||||
// Timing parameters
|
// Timing parameters
|
||||||
|
@ -92,9 +91,9 @@ enum {
|
||||||
|
|
||||||
|
|
||||||
// convert between 'saDevice.channel' and band/channel values
|
// convert between 'saDevice.channel' and band/channel values
|
||||||
#define SA_DEVICE_CHVAL_TO_BAND(val) ((val) / (uint8_t)8)
|
#define SA_DEVICE_CHVAL_TO_BAND(val) ((val) / (uint8_t)vtxTableChannelCount) + 1
|
||||||
#define SA_DEVICE_CHVAL_TO_CHANNEL(val) ((val) % (uint8_t)8)
|
#define SA_DEVICE_CHVAL_TO_CHANNEL(val) ((val) % (uint8_t)vtxTableChannelCount) + 1
|
||||||
#define SA_BANDCHAN_TO_DEVICE_CHVAL(band, channel) ((band) * (uint8_t)8 + (channel))
|
#define SA_BANDCHAN_TO_DEVICE_CHVAL(band, channel) ((band - 1) * (uint8_t)vtxTableChannelCount + (channel - 1))
|
||||||
|
|
||||||
|
|
||||||
// Statistical counters, for user side trouble shooting.
|
// Statistical counters, for user side trouble shooting.
|
||||||
|
@ -118,6 +117,7 @@ smartAudioDevice_t saDevice = {
|
||||||
.mode = 0,
|
.mode = 0,
|
||||||
.freq = 0,
|
.freq = 0,
|
||||||
.orfreq = 0,
|
.orfreq = 0,
|
||||||
|
.willBootIntoPitMode = false,
|
||||||
};
|
};
|
||||||
|
|
||||||
static smartAudioDevice_t saDevicePrev = {
|
static smartAudioDevice_t saDevicePrev = {
|
||||||
|
@ -139,7 +139,7 @@ bool saDeferred = true; // saCms variable?
|
||||||
|
|
||||||
// Receive frame reassembly buffer
|
// Receive frame reassembly buffer
|
||||||
#define SA_MAX_RCVLEN 21
|
#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
|
// CRC8 computations
|
||||||
|
@ -182,9 +182,9 @@ static void saPrintSettings(void)
|
||||||
dprintf((" channel: %d ", saDevice.channel));
|
dprintf((" channel: %d ", saDevice.channel));
|
||||||
dprintf(("freq: %d ", saDevice.freq));
|
dprintf(("freq: %d ", saDevice.freq));
|
||||||
dprintf(("power: %d ", saDevice.power));
|
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(("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"));
|
dprintf(("\r\n"));
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -208,7 +208,7 @@ static void saAutobaud(void)
|
||||||
|
|
||||||
#if 0
|
#if 0
|
||||||
dprintf(("autobaud: %d rcvd %d/%d (%d)\r\n",
|
dprintf(("autobaud: %d rcvd %d/%d (%d)\r\n",
|
||||||
sa_smartbaud, saStat.pktrcvd, saStat.pktsent, ((saStat.pktrcvd * 100) / saStat.pktsent)));
|
sa_smartbaud, saStat.pktrcvd, saStat.pktsent, ((saStat.pktrcvd * 100) / saStat.pktsent)));
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (((saStat.pktrcvd * 100) / saStat.pktsent) >= 70) {
|
if (((saStat.pktrcvd * 100) / saStat.pktsent) >= 70) {
|
||||||
|
@ -221,11 +221,11 @@ static void saAutobaud(void)
|
||||||
dprintf(("autobaud: adjusting\r\n"));
|
dprintf(("autobaud: adjusting\r\n"));
|
||||||
|
|
||||||
if ((sa_adjdir == 1) && (sa_smartbaud == SMARTBAUD_MAX)) {
|
if ((sa_adjdir == 1) && (sa_smartbaud == SMARTBAUD_MAX)) {
|
||||||
sa_adjdir = -1;
|
sa_adjdir = -1;
|
||||||
dprintf(("autobaud: now going down\r\n"));
|
dprintf(("autobaud: now going down\r\n"));
|
||||||
} else if ((sa_adjdir == -1 && sa_smartbaud == SMARTBAUD_MIN)) {
|
} else if ((sa_adjdir == -1 && sa_smartbaud == SMARTBAUD_MIN)) {
|
||||||
sa_adjdir = 1;
|
sa_adjdir = 1;
|
||||||
dprintf(("autobaud: now going up\r\n"));
|
dprintf(("autobaud: now going up\r\n"));
|
||||||
}
|
}
|
||||||
|
|
||||||
sa_smartbaud += sa_baudstep * sa_adjdir;
|
sa_smartbaud += sa_baudstep * sa_adjdir;
|
||||||
|
@ -281,7 +281,7 @@ static void saProcessResponse(uint8_t *buf, int len)
|
||||||
saDevice.channel = buf[2];
|
saDevice.channel = buf[2];
|
||||||
uint8_t rawPowerValue = buf[3];
|
uint8_t rawPowerValue = buf[3];
|
||||||
saDevice.mode = buf[4];
|
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.
|
// 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.
|
// 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) {
|
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);
|
bool newBootMode = (saDevice.mode & SA_MODE_GET_IN_RANGE_PITMODE) || (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE);
|
||||||
if (newBootMode != saDevice.willBootIntoPitMode) {
|
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;
|
saDevice.willBootIntoPitMode = newBootMode;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(saDevice.version == 3) {
|
if (saDevice.version == 3) {
|
||||||
//read dbm based power levels
|
//read dbm based power levels
|
||||||
//aaaaaand promptly forget them. todo: write them into vtxtable pg and load it
|
//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"));
|
dprintf(("processResponse: V2.1 vtx didn't report any power levels\r\n"));
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -323,8 +323,8 @@ static void saProcessResponse(uint8_t *buf, int len)
|
||||||
}
|
}
|
||||||
|
|
||||||
dprintf(("processResponse: %d power values: %d, %d, %d, %d\r\n",
|
dprintf(("processResponse: %d power values: %d, %d, %d, %d\r\n",
|
||||||
vtxSmartAudio.capability.powerCount, vtxSmartAudio.powerValues[0], vtxSmartAudio.powerValues[1],
|
vtxTablePowerLevels, vtxTablePowerValues[0], vtxTablePowerValues[1],
|
||||||
vtxSmartAudio.powerValues[2], vtxSmartAudio.powerValues[3]));
|
vtxTablePowerValues[2], vtxTablePowerValues[3]));
|
||||||
//dprintf(("processResponse: V2.1 received vtx power value %d\r\n",buf[7]));
|
//dprintf(("processResponse: V2.1 received vtx power value %d\r\n",buf[7]));
|
||||||
rawPowerValue = buf[7];
|
rawPowerValue = buf[7];
|
||||||
}
|
}
|
||||||
|
@ -333,8 +333,8 @@ static void saProcessResponse(uint8_t *buf, int len)
|
||||||
#endif
|
#endif
|
||||||
saDevice.power = 0;//set to unknown power level if the reported one doesnt match any of the known ones
|
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]));
|
dprintf(("processResponse: rawPowerValue is %d, legacy power is %d\r\n", rawPowerValue, buf[3]));
|
||||||
for (int8_t i = 0; i < vtxSmartAudio.capability.powerCount; i++) {
|
for (int8_t i = 0; i < vtxTablePowerLevels; i++) {
|
||||||
if(rawPowerValue == vtxSmartAudio.powerValues[i]) {
|
if (rawPowerValue == vtxTablePowerValues[i]) {
|
||||||
#ifdef USE_SMARTAUDIO_DPRINTF
|
#ifdef USE_SMARTAUDIO_DPRINTF
|
||||||
if (prevPower != i + 1) {
|
if (prevPower != i + 1) {
|
||||||
dprintf(("processResponse: power changed from index %d to index %d\r\n", 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;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
const uint16_t freq = (buf[2] << 8)|buf[3];
|
const uint16_t freq = (buf[2] << 8) | buf[3];
|
||||||
|
|
||||||
if (freq & SA_FREQ_GETPIT) {
|
if (freq & SA_FREQ_GETPIT) {
|
||||||
saDevice.orfreq = freq & SA_FREQ_MASK;
|
saDevice.orfreq = freq & SA_FREQ_MASK;
|
||||||
|
@ -378,8 +378,8 @@ static void saProcessResponse(uint8_t *buf, int len)
|
||||||
|
|
||||||
case SA_CMD_SET_MODE: // Set Mode
|
case SA_CMD_SET_MODE: // Set Mode
|
||||||
dprintf(("saProcessResponse: SET_MODE 0x%x (pir %s, por %s, pitdsbl %s, %s)\r\n",
|
dprintf(("saProcessResponse: SET_MODE 0x%x (pir %s, por %s, pitdsbl %s, %s)\r\n",
|
||||||
buf[2], (buf[2] & 1) ? "on" : "off", (buf[2] & 2) ? "on" : "off", (buf[3] & 4) ? "on" : "off",
|
buf[2], (buf[2] & 1) ? "on" : "off", (buf[2] & 2) ? "on" : "off", (buf[3] & 4) ? "on" : "off",
|
||||||
(buf[4] & 8) ? "unlocked" : "locked"));
|
(buf[4] & 8) ? "unlocked" : "locked"));
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
|
@ -494,12 +494,12 @@ static void saSendFrame(uint8_t *buf, int len)
|
||||||
{
|
{
|
||||||
if (!IS_RC_MODE_ACTIVE(BOXVTXCONTROLDISABLE)) {
|
if (!IS_RC_MODE_ACTIVE(BOXVTXCONTROLDISABLE)) {
|
||||||
switch (smartAudioSerialPort->identifier) {
|
switch (smartAudioSerialPort->identifier) {
|
||||||
case SERIAL_PORT_SOFTSERIAL1:
|
case SERIAL_PORT_SOFTSERIAL1:
|
||||||
case SERIAL_PORT_SOFTSERIAL2:
|
case SERIAL_PORT_SOFTSERIAL2:
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
serialWrite(smartAudioSerialPort, 0x00); // Generate 1st start bit
|
serialWrite(smartAudioSerialPort, 0x00); // Generate 1st start bit
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int i = 0 ; i < len ; i++) {
|
for (int i = 0 ; i < len ; i++) {
|
||||||
|
@ -576,7 +576,7 @@ static bool saQueueFull(void)
|
||||||
static void saQueueCmd(uint8_t *buf, int len)
|
static void saQueueCmd(uint8_t *buf, int len)
|
||||||
{
|
{
|
||||||
if (saQueueFull()) {
|
if (saQueueFull()) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
sa_queue[sa_qhead].buf = buf;
|
sa_queue[sa_qhead].buf = buf;
|
||||||
|
@ -609,7 +609,7 @@ static bool saValidateFreq(uint16_t freq)
|
||||||
return (freq >= VTX_SMARTAUDIO_MIN_FREQUENCY_MHZ && freq <= VTX_SMARTAUDIO_MAX_FREQUENCY_MHZ);
|
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 buf[7] = { 0xAA, 0x55, SACMD(SA_CMD_SET_FREQ), 2 };
|
||||||
static uint8_t switchBuf[7];
|
static uint8_t switchBuf[7];
|
||||||
|
@ -645,14 +645,9 @@ static void saDoDevSetFreq(uint16_t freq)
|
||||||
saQueueCmd(buf, 7);
|
saQueueCmd(buf, 7);
|
||||||
}
|
}
|
||||||
|
|
||||||
void saSetFreq(uint16_t freq)
|
|
||||||
{
|
|
||||||
saDoDevSetFreq(freq);
|
|
||||||
}
|
|
||||||
|
|
||||||
void saSetPitFreq(uint16_t freq)
|
void saSetPitFreq(uint16_t freq)
|
||||||
{
|
{
|
||||||
saDoDevSetFreq(freq | SA_FREQ_SETPIT);
|
saSetFreq(freq | SA_FREQ_SETPIT);
|
||||||
}
|
}
|
||||||
|
|
||||||
#if 0
|
#if 0
|
||||||
|
@ -662,34 +657,12 @@ static void saGetPitFreq(void)
|
||||||
}
|
}
|
||||||
#endif
|
#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)
|
void saSetMode(int mode)
|
||||||
{
|
{
|
||||||
static uint8_t buf[6] = { 0xAA, 0x55, SACMD(SA_CMD_SET_MODE), 1 };
|
static uint8_t buf[6] = { 0xAA, 0x55, SACMD(SA_CMD_SET_MODE), 1 };
|
||||||
|
|
||||||
buf[4] = (mode & 0x3f)|saLockMode;
|
buf[4] = (mode & 0x3f) | saLockMode;
|
||||||
if (saDevice.version>=3 && (mode & SA_MODE_CLR_PITMODE) &&
|
if (saDevice.version >= 3 && (mode & SA_MODE_CLR_PITMODE) &&
|
||||||
((mode & SA_MODE_SET_IN_RANGE_PITMODE) || (mode & SA_MODE_SET_OUT_RANGE_PITMODE))) {
|
((mode & SA_MODE_SET_IN_RANGE_PITMODE) || (mode & SA_MODE_SET_OUT_RANGE_PITMODE))) {
|
||||||
saDevice.willBootIntoPitMode = true;//quit pitmode without unsetting flag.
|
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.
|
//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;
|
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;
|
saSupportedPowerValues[i] = 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_VTX_TABLE
|
dprintf(("vtxSmartAudioInit %d power levels recorded\r\n", vtxTablePowerLevels));
|
||||||
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
|
|
||||||
|
|
||||||
vtxCommonSetDevice(&vtxSmartAudio);
|
vtxCommonSetDevice(&vtxSmartAudio);
|
||||||
|
#ifndef USE_VTX_TABLE
|
||||||
|
vtxTableSetFactoryBands(true);
|
||||||
|
#endif
|
||||||
|
|
||||||
vtxInit();
|
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.
|
// Also don't send it to V2.1 for the same reason.
|
||||||
if (saDevice.version) {
|
if (saDevice.version) {
|
||||||
if (saDevice.version == 2) {
|
if (saDevice.version == 2) {
|
||||||
saDoDevSetFreq(SA_FREQ_GETPIT);
|
saSetFreq(SA_FREQ_GETPIT);
|
||||||
initPhase = SA_INITPHASE_WAIT_PITFREQ;
|
initPhase = SA_INITPHASE_WAIT_PITFREQ;
|
||||||
} else {
|
} else {
|
||||||
initPhase = SA_INITPHASE_DONE;
|
initPhase = SA_INITPHASE_DONE;
|
||||||
|
@ -818,20 +776,28 @@ static void vtxSAProcess(vtxDevice_t *vtxDevice, timeUs_t currentTimeUs)
|
||||||
saSupportedPowerValues[1] = 16;
|
saSupportedPowerValues[1] = 16;
|
||||||
saSupportedPowerValues[2] = 25;
|
saSupportedPowerValues[2] = 25;
|
||||||
saSupportedPowerValues[3] = 40;
|
saSupportedPowerValues[3] = 40;
|
||||||
}else if(saDevice.version == 2) {
|
} else if (saDevice.version == 2) {
|
||||||
saSupportedPowerValues[0] = 0;
|
saSupportedPowerValues[0] = 0;
|
||||||
saSupportedPowerValues[1] = 1;
|
saSupportedPowerValues[1] = 1;
|
||||||
saSupportedPowerValues[2] = 2;
|
saSupportedPowerValues[2] = 2;
|
||||||
saSupportedPowerValues[3] = 3;
|
saSupportedPowerValues[3] = 3;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (saDevice.version >= 2) {//V2.0 and V1.0 use defaults set at declaration
|
//without USE_VTX_TABLE, fill vtxTable variables with default settings (instead of loading them from PG)
|
||||||
vtxSmartAudio.capability.powerCount = constrain(saSupportedNumPowerLevels, 0, VTX_SMARTAUDIO_POWER_COUNT);
|
vtxTablePowerLevels = constrain(saSupportedNumPowerLevels, 0, VTX_SMARTAUDIO_POWER_COUNT);
|
||||||
for(int8_t i = 0; i < saSupportedNumPowerLevels; i++) {
|
if (saDevice.version >= 3) {
|
||||||
tfp_sprintf(saSupportedPowerLabels[i + 1], "%3d", constrain(saSupportedPowerValues[i], 0, 999));
|
for (int8_t i = 0; i < vtxTablePowerLevels; i++) {
|
||||||
//ideally we would convert dbm to mW here
|
//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
|
#endif
|
||||||
|
|
||||||
if (saDevice.version >= 2 ) {
|
if (saDevice.version >= 2 ) {
|
||||||
|
@ -862,16 +828,17 @@ static void vtxSAProcess(vtxDevice_t *vtxDevice, timeUs_t currentTimeUs)
|
||||||
dprintf(("process: resending 0x%x\r\n", sa_outstanding));
|
dprintf(("process: resending 0x%x\r\n", sa_outstanding));
|
||||||
// XXX Todo: Resend termination and possible offline transition
|
// XXX Todo: Resend termination and possible offline transition
|
||||||
saResendCmd();
|
saResendCmd();
|
||||||
lastCommandSentMs = nowMs;
|
lastCommandSentMs = nowMs;
|
||||||
} else if (!saQueueEmpty()) {
|
} else if (!saQueueEmpty()) {
|
||||||
// Command pending. Send it.
|
// Command pending. Send it.
|
||||||
dprintf(("process: sending queue\r\n"));
|
dprintf(("process: sending queue\r\n"));
|
||||||
saSendQueue();
|
saSendQueue();
|
||||||
lastCommandSentMs = nowMs;
|
lastCommandSentMs = nowMs;
|
||||||
} else if ((nowMs - lastCommandSentMs < SMARTAUDIO_POLLING_WINDOW) && (nowMs - sa_lastTransmissionMs >= SMARTAUDIO_POLLING_INTERVAL)) {
|
} else if ((nowMs - lastCommandSentMs < SMARTAUDIO_POLLING_WINDOW)
|
||||||
dprintf(("process: sending status change polling\r\n"));
|
&& (nowMs - sa_lastTransmissionMs >= SMARTAUDIO_POLLING_INTERVAL)) {
|
||||||
saGetSettings();
|
dprintf(("process: sending status change polling\r\n"));
|
||||||
saSendQueue();
|
saGetSettings();
|
||||||
|
saSendQueue();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#ifdef USE_VTX_COMMON
|
#ifdef USE_VTX_COMMON
|
||||||
|
@ -885,14 +852,39 @@ vtxDevType_e vtxSAGetDeviceType(const vtxDevice_t *vtxDevice)
|
||||||
|
|
||||||
static bool vtxSAIsReady(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)
|
static void vtxSASetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channel)
|
||||||
{
|
{
|
||||||
UNUSED(vtxDevice);
|
UNUSED(vtxDevice);
|
||||||
if (saValidateBandAndChannel(band, channel)) {
|
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;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (index <= 0 || index > vtxSmartAudio.capability.powerCount) {
|
uint16_t powerValue = 0;
|
||||||
dprintf(("saSetPowerByIndex: cannot get power level %d, only levels 1 through %d supported", index, vtxSmartAudio.capability.powerCount));
|
if (!vtxCommonLookupPowerValue(vtxDevice, index, &powerValue)) {
|
||||||
|
dprintf(("saSetPowerByIndex: cannot get power level %d, only levels 1 through %d supported", index,
|
||||||
|
vtxTablePowerLevels));
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
buf[4] = vtxSmartAudio.powerValues[index - 1];//use vtxcommonlookuppowervalue instead?
|
buf[4] = powerValue;
|
||||||
dprintf(("saSetPowerByIndex: index %d, value %d\r\n", index, buf[4]));
|
dprintf(("saSetPowerByIndex: index %d, value %d\r\n", index, buf[4]));
|
||||||
if (saDevice.version == 3) {
|
if (saDevice.version == 3) {
|
||||||
buf[4] |= 128;//set MSB to indicate set power by dbm
|
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;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(saDevice.version >= 3 && !saDevice.willBootIntoPitMode) {
|
if (saDevice.version >= 3 && !saDevice.willBootIntoPitMode) {
|
||||||
if (onoff) {
|
if (onoff) {
|
||||||
// enable pitmode using SET_POWER command with 0 dbm.
|
// enable pitmode using SET_POWER command with 0 dbm.
|
||||||
// This enables pitmode without causing the device to boot into pitmode next power-up
|
// 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)
|
static void vtxSASetFreq(vtxDevice_t *vtxDevice, uint16_t freq)
|
||||||
{
|
{
|
||||||
UNUSED(vtxDevice);
|
if (!vtxSAIsReady(vtxDevice)) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
if (saValidateFreq(freq)) {
|
if (saValidateFreq(freq)) {
|
||||||
saSetMode(0); //need to be in FREE mode to set freq
|
|
||||||
saSetFreq(freq);
|
saSetFreq(freq);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -980,11 +976,15 @@ static bool vtxSAGetBandAndChannel(const vtxDevice_t *vtxDevice, uint8_t *pBand,
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// if in user-freq mode then report band as zero
|
if (saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ) {
|
||||||
*pBand = (saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ) ? 0 :
|
*pBand = 0;
|
||||||
(SA_DEVICE_CHVAL_TO_BAND(saDevice.channel) + 1);
|
*pChannel = 0;
|
||||||
*pChannel = SA_DEVICE_CHVAL_TO_CHANNEL(saDevice.channel) + 1;
|
return true;
|
||||||
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)
|
static bool vtxSAGetPowerIndex(const vtxDevice_t *vtxDevice, uint8_t *pIndex)
|
||||||
|
@ -1015,9 +1015,9 @@ static bool vtxSAGetFreq(const vtxDevice_t *vtxDevice, uint16_t *pFreq)
|
||||||
|
|
||||||
// if not in user-freq mode then convert band/chan to frequency
|
// if not in user-freq mode then convert band/chan to frequency
|
||||||
*pFreq = (saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ) ? saDevice.freq :
|
*pFreq = (saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ) ? saDevice.freq :
|
||||||
vtxCommonLookupFrequency(&vtxSmartAudio,
|
vtxCommonLookupFrequency(&vtxSmartAudio,
|
||||||
SA_DEVICE_CHVAL_TO_BAND(saDevice.channel) + 1,
|
SA_DEVICE_CHVAL_TO_BAND(saDevice.channel),
|
||||||
SA_DEVICE_CHVAL_TO_CHANNEL(saDevice.channel) + 1);
|
SA_DEVICE_CHVAL_TO_CHANNEL(saDevice.channel));
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -25,7 +25,6 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
//#define USE_SMARTAUDIO_DPRINTF
|
|
||||||
#ifdef USE_SMARTAUDIO_DPRINTF
|
#ifdef USE_SMARTAUDIO_DPRINTF
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "common/printf.h"
|
#include "common/printf.h"
|
||||||
|
@ -33,15 +32,10 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define VTX_SMARTAUDIO_MIN_BAND 1
|
#define VTX_SMARTAUDIO_MIN_BAND 1
|
||||||
#define VTX_SMARTAUDIO_MAX_BAND 5
|
|
||||||
#define VTX_SMARTAUDIO_MIN_CHANNEL 1
|
#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_POWER_COUNT 4
|
||||||
#define VTX_SMARTAUDIO_DEFAULT_POWER 1
|
|
||||||
|
|
||||||
#define VTX_SMARTAUDIO_MIN_FREQUENCY_MHZ 5000 //min freq in MHz
|
#define VTX_SMARTAUDIO_MIN_FREQUENCY_MHZ 5000 //min freq in MHz
|
||||||
#define VTX_SMARTAUDIO_MAX_FREQUENCY_MHZ 5999 //max 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 uint16_t sa_smartbaud;
|
||||||
extern bool saDeferred;
|
extern bool saDeferred;
|
||||||
|
|
||||||
void saSetBandAndChannel(uint8_t band, uint8_t channel);
|
|
||||||
void saSetMode(int mode);
|
void saSetMode(int mode);
|
||||||
void saSetFreq(uint16_t freq);
|
void saSetFreq(uint16_t freq);
|
||||||
void saSetPitFreq(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 "cms/cms_menu_vtx_tramp.h"
|
||||||
|
|
||||||
#include "drivers/vtx_common.h"
|
#include "drivers/vtx_common.h"
|
||||||
|
|
||||||
#ifdef USE_VTX_TABLE
|
|
||||||
#include "drivers/vtx_table.h"
|
#include "drivers/vtx_table.h"
|
||||||
#endif
|
|
||||||
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "io/vtx_tramp.h"
|
#include "io/vtx_tramp.h"
|
||||||
#include "io/vtx_control.h"
|
#include "io/vtx_control.h"
|
||||||
#include "io/vtx.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] = {
|
const uint16_t trampPowerTable[VTX_TRAMP_POWER_COUNT] = {
|
||||||
25, 100, 200, 400, 600
|
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"
|
"---", "25 ", "100", "200", "400", "600"
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
@ -84,10 +80,7 @@ uint32_t trampRFFreqMin;
|
||||||
uint32_t trampRFFreqMax;
|
uint32_t trampRFFreqMax;
|
||||||
uint32_t trampRFPowerMax;
|
uint32_t trampRFPowerMax;
|
||||||
|
|
||||||
bool trampSetByFreqFlag = false; //false = set via band/channel
|
|
||||||
uint32_t trampCurFreq = 0;
|
uint32_t trampCurFreq = 0;
|
||||||
uint8_t trampBand = 0;
|
|
||||||
uint8_t trampChannel = 0;
|
|
||||||
uint16_t trampPower = 0; // Actual transmitting power
|
uint16_t trampPower = 0; // Actual transmitting power
|
||||||
uint16_t trampConfiguredPower = 0; // Configured transmitting power
|
uint16_t trampConfiguredPower = 0; // Configured transmitting power
|
||||||
int16_t trampTemperature = 0;
|
int16_t trampTemperature = 0;
|
||||||
|
@ -148,7 +141,6 @@ static void trampDevSetFreq(uint16_t freq)
|
||||||
|
|
||||||
void trampSetFreq(uint16_t freq)
|
void trampSetFreq(uint16_t freq)
|
||||||
{
|
{
|
||||||
trampSetByFreqFlag = true; //set freq via MHz value
|
|
||||||
trampDevSetFreq(freq);
|
trampDevSetFreq(freq);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -157,23 +149,6 @@ void trampSendFreq(uint16_t freq)
|
||||||
trampCmdU16('F', 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)
|
void trampSetRFPower(uint16_t level)
|
||||||
{
|
{
|
||||||
trampConfPower = level;
|
trampConfPower = level;
|
||||||
|
@ -198,17 +173,6 @@ bool trampCommitChanges(void)
|
||||||
return true;
|
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)
|
void trampSetPitMode(uint8_t onoff)
|
||||||
{
|
{
|
||||||
trampCmdU16('I', onoff ? 0 : 1);
|
trampCmdU16('I', onoff ? 0 : 1);
|
||||||
|
@ -243,11 +207,6 @@ static char trampHandleResponse(void)
|
||||||
trampPitMode = trampRespBuffer[7];
|
trampPitMode = trampRespBuffer[7];
|
||||||
trampPower = trampRespBuffer[8]|(trampRespBuffer[9] << 8);
|
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 (trampConfFreq == 0) trampConfFreq = trampCurFreq;
|
||||||
if (trampConfPower == 0) trampConfPower = trampPower;
|
if (trampConfPower == 0) trampConfPower = trampPower;
|
||||||
return 'v';
|
return 'v';
|
||||||
|
@ -403,10 +362,10 @@ static void vtxTrampProcess(vtxDevice_t *vtxDevice, timeUs_t currentTimeUs)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 'v':
|
case 'v':
|
||||||
if (trampStatus == TRAMP_STATUS_CHECK_FREQ_PW) {
|
if (trampStatus == TRAMP_STATUS_CHECK_FREQ_PW) {
|
||||||
trampStatus = TRAMP_STATUS_SET_FREQ_PW;
|
trampStatus = TRAMP_STATUS_SET_FREQ_PW;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
switch (trampStatus) {
|
switch (trampStatus) {
|
||||||
|
@ -500,22 +459,24 @@ static vtxDevType_e vtxTrampGetDeviceType(const vtxDevice_t *vtxDevice)
|
||||||
|
|
||||||
static bool vtxTrampIsReady(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)
|
static void vtxTrampSetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channel)
|
||||||
{
|
{
|
||||||
UNUSED(vtxDevice);
|
UNUSED(vtxDevice);
|
||||||
if (trampValidateBandAndChannel(band, channel)) {
|
UNUSED(band);
|
||||||
trampSetBandAndChannel(band, channel);
|
UNUSED(channel);
|
||||||
trampCommitChanges();
|
//tramp does not support band/channel mode, only frequency
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
static void vtxTrampSetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index)
|
static void vtxTrampSetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index)
|
||||||
{
|
{
|
||||||
UNUSED(vtxDevice);
|
uint16_t powerValue = 0;
|
||||||
trampDevSetPowerByIndex(index);
|
if (vtxCommonLookupPowerValue(vtxDevice, index, &powerValue)) {
|
||||||
|
trampSetRFPower(powerValue);
|
||||||
|
trampCommitChanges();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static void vtxTrampSetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff)
|
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;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// if in user-freq mode then report band as zero
|
// tramp does not support band and channel
|
||||||
*pBand = trampSetByFreqFlag ? 0 : trampBand;
|
*pBand = 0;
|
||||||
*pChannel = trampChannel;
|
*pChannel = 0;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -552,8 +513,8 @@ static bool vtxTrampGetPowerIndex(const vtxDevice_t *vtxDevice, uint8_t *pIndex)
|
||||||
}
|
}
|
||||||
|
|
||||||
if (trampConfiguredPower > 0) {
|
if (trampConfiguredPower > 0) {
|
||||||
for (uint8_t i = 0; i < vtxTramp.capability.powerCount; i++) {
|
for (uint8_t i = 0; i < vtxTablePowerLevels; i++) {
|
||||||
if (trampConfiguredPower <= vtxTramp.powerValues[i]) {
|
if (trampConfiguredPower <= vtxTablePowerValues[i]) {
|
||||||
*pIndex = i + 1;
|
*pIndex = i + 1;
|
||||||
break;
|
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.
|
// 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_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);
|
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
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -22,16 +22,7 @@
|
||||||
|
|
||||||
#include <stdint.h>
|
#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_POWER_COUNT 5
|
||||||
#define VTX_TRAMP_DEFAULT_POWER 1
|
|
||||||
|
|
||||||
#define VTX_TRAMP_MIN_FREQUENCY_MHZ 5000 //min freq in MHz
|
#define VTX_TRAMP_MIN_FREQUENCY_MHZ 5000 //min freq in MHz
|
||||||
#define VTX_TRAMP_MAX_FREQUENCY_MHZ 5999 //max 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/usb_msc.h"
|
||||||
#include "io/vtx_control.h"
|
#include "io/vtx_control.h"
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
#include "io/vtx_string.h"
|
|
||||||
|
|
||||||
#include "msp/msp_box.h"
|
#include "msp/msp_box.h"
|
||||||
#include "msp/msp_protocol.h"
|
#include "msp/msp_protocol.h"
|
||||||
|
|
|
@ -20,6 +20,8 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#ifdef USE_VTX_TABLE
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stdbool.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 bandNames[VTX_TABLE_MAX_BANDS][VTX_TABLE_BAND_NAME_LENGTH + 1];
|
||||||
char bandLetters[VTX_TABLE_MAX_BANDS];
|
char bandLetters[VTX_TABLE_MAX_BANDS];
|
||||||
char channelNames[VTX_TABLE_MAX_CHANNELS][VTX_TABLE_CHANNEL_NAME_LENGTH + 1];
|
char channelNames[VTX_TABLE_MAX_CHANNELS][VTX_TABLE_CHANNEL_NAME_LENGTH + 1];
|
||||||
|
bool isFactoryBand[VTX_TABLE_MAX_BANDS];
|
||||||
|
|
||||||
uint8_t powerLevels;
|
uint8_t powerLevels;
|
||||||
uint16_t powerValues[VTX_TABLE_MAX_POWER_LEVELS];
|
uint16_t powerValues[VTX_TABLE_MAX_POWER_LEVELS];
|
||||||
|
@ -41,3 +44,5 @@ typedef struct vtxTableConfig_s {
|
||||||
|
|
||||||
struct vtxTableConfig_s;
|
struct vtxTableConfig_s;
|
||||||
PG_DECLARE(struct vtxTableConfig_s, vtxTableConfig);
|
PG_DECLARE(struct vtxTableConfig_s, vtxTableConfig);
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -557,25 +557,22 @@ static void convertVtxPower(spektrumVtx_t * vtx)
|
||||||
{
|
{
|
||||||
uint8_t const * powerIndexTable = NULL;
|
uint8_t const * powerIndexTable = NULL;
|
||||||
|
|
||||||
|
vtxCommonLookupPowerValue(vtxCommonDevice(), vtx->power, &vtx->powerValue);
|
||||||
switch (vtxDeviceType) {
|
switch (vtxDeviceType) {
|
||||||
|
|
||||||
#if defined(USE_VTX_TRAMP)
|
#if defined(USE_VTX_TRAMP)
|
||||||
case VTXDEV_TRAMP:
|
case VTXDEV_TRAMP:
|
||||||
powerIndexTable = vtxTrampPi;
|
powerIndexTable = vtxTrampPi;
|
||||||
vtx->powerValue = vtxCommonLookupPowerValue(vtxCommonDevice(), vtx->power - 1); // Lookup the device power value, 0-based table vs 1-based index. Doh.
|
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
#if defined(USE_VTX_SMARTAUDIO)
|
#if defined(USE_VTX_SMARTAUDIO)
|
||||||
case VTXDEV_SMARTAUDIO:
|
case VTXDEV_SMARTAUDIO:
|
||||||
powerIndexTable = vtxSaPi;
|
powerIndexTable = vtxSaPi;
|
||||||
vtx->powerValue = vtxCommonLookupPowerValue(vtxCommonDevice(), vtx->power - 1); // Lookup the device power value, 0-based table vs 1-based index. Doh.
|
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
#if defined(USE_VTX_RTC6705)
|
#if defined(USE_VTX_RTC6705)
|
||||||
case VTXDEV_RTC6705:
|
case VTXDEV_RTC6705:
|
||||||
powerIndexTable = vtxRTC6705Pi;
|
powerIndexTable = vtxRTC6705Pi;
|
||||||
// No power value table available.Hard code some "knowledge" here. Doh.
|
|
||||||
vtx->powerValue = vtx->power == VTX_6705_POWER_200 ? 200 : 25;
|
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -382,8 +382,8 @@ vtx_unittest_SRC := \
|
||||||
$(USER_DIR)/fc/rc_modes.c \
|
$(USER_DIR)/fc/rc_modes.c \
|
||||||
$(USER_DIR)/fc/runtime_config.c \
|
$(USER_DIR)/fc/runtime_config.c \
|
||||||
$(USER_DIR)/drivers/vtx_common.c \
|
$(USER_DIR)/drivers/vtx_common.c \
|
||||||
|
$(USER_DIR)/drivers/vtx_table.c \
|
||||||
$(USER_DIR)/io/vtx_control.c \
|
$(USER_DIR)/io/vtx_control.c \
|
||||||
$(USER_DIR)/io/vtx_string.c \
|
|
||||||
$(USER_DIR)/io/vtx.c \
|
$(USER_DIR)/io/vtx.c \
|
||||||
$(USER_DIR)/common/bitarray.c
|
$(USER_DIR)/common/bitarray.c
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue