Spektrum VTX control moved to VTX control task. Added some missing compile conditionals and a few cosmetic updates too.
This commit is contained in:
parent
06326c8b69
commit
ac76179942
|
@ -321,6 +321,7 @@ SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
|
||||||
io/vtx_smartaudio.c \
|
io/vtx_smartaudio.c \
|
||||||
io/vtx_tramp.c \
|
io/vtx_tramp.c \
|
||||||
io/vtx_control.c \
|
io/vtx_control.c \
|
||||||
|
io/spektrum_vtx_control.c \
|
||||||
pg/pg.h
|
pg/pg.h
|
||||||
|
|
||||||
# F4 and F7 optimizations
|
# F4 and F7 optimizations
|
||||||
|
|
|
@ -54,6 +54,7 @@ const uint8_t spek2commonBand[]= {
|
||||||
|
|
||||||
// RF Power Index translation tables. No generic power API available.....
|
// RF Power Index translation tables. No generic power API available.....
|
||||||
|
|
||||||
|
#ifdef USE_VTX_TRAMP
|
||||||
// Tramp "---", 25, 200, 400. 600 mW
|
// Tramp "---", 25, 200, 400. 600 mW
|
||||||
const uint8_t vtxTrampPi[] = { // Spektrum Spec Tx menu Tx sends To VTX Watt
|
const uint8_t vtxTrampPi[] = { // Spektrum Spec Tx menu Tx sends To VTX Watt
|
||||||
VTX_TRAMP_POWER_OFF, // Off INHIBIT 0 0 -
|
VTX_TRAMP_POWER_OFF, // Off INHIBIT 0 0 -
|
||||||
|
@ -65,7 +66,9 @@ const uint8_t vtxTrampPi[] = { // Spektrum Spec Tx menu Tx sends T
|
||||||
VTX_TRAMP_POWER_600, // 601 - max 601+ mW 6 5 600mW Slightly outside range
|
VTX_TRAMP_POWER_600, // 601 - max 601+ mW 6 5 600mW Slightly outside range
|
||||||
VTX_TRAMP_POWER_200 // Manual - - - -
|
VTX_TRAMP_POWER_200 // Manual - - - -
|
||||||
};
|
};
|
||||||
|
#endif // USE_VTX_TRAMP
|
||||||
|
|
||||||
|
#ifdef USE_VTX_RTC6705
|
||||||
// RTC6705 "---", 25 or 200 mW
|
// RTC6705 "---", 25 or 200 mW
|
||||||
const uint8_t vtxRTC6705Pi[] = {
|
const uint8_t vtxRTC6705Pi[] = {
|
||||||
VTX_6705_POWER_OFF, // Off
|
VTX_6705_POWER_OFF, // Off
|
||||||
|
@ -77,7 +80,9 @@ const uint8_t vtxRTC6705Pi[] = {
|
||||||
VTX_6705_POWER_200, // 601 - max
|
VTX_6705_POWER_200, // 601 - max
|
||||||
VTX_6705_POWER_200 // Manual
|
VTX_6705_POWER_200 // Manual
|
||||||
};
|
};
|
||||||
|
#endif //USE_VTX_RTC6705
|
||||||
|
|
||||||
|
#ifdef USE_VTX_SMARTAUDIO
|
||||||
// SmartAudio "---", 25, 200, 500. 800 mW
|
// SmartAudio "---", 25, 200, 500. 800 mW
|
||||||
const uint8_t vtxSaPi[] = {
|
const uint8_t vtxSaPi[] = {
|
||||||
VTX_SA_POWER_OFF, // Off
|
VTX_SA_POWER_OFF, // Off
|
||||||
|
@ -89,23 +94,30 @@ const uint8_t vtxSaPi[] = {
|
||||||
VTX_SA_POWER_800, // 601 - max
|
VTX_SA_POWER_800, // 601 - max
|
||||||
VTX_SA_POWER_200 // Manual
|
VTX_SA_POWER_200 // Manual
|
||||||
};
|
};
|
||||||
|
#endif // USE_VTX_SMARTAUDIO
|
||||||
|
|
||||||
uint8_t convertSpektrumVtxPowerIndex(uint8_t sPower)
|
uint8_t convertSpektrumVtxPowerIndex(uint8_t sPower)
|
||||||
{
|
{
|
||||||
uint8_t devicePower = 0;
|
uint8_t devicePower = 0;
|
||||||
|
|
||||||
switch (vtxCommonGetDeviceType()) {
|
switch (vtxCommonGetDeviceType()) {
|
||||||
|
#ifdef USE_VTX_RTC6705
|
||||||
case VTXDEV_RTC6705:
|
case VTXDEV_RTC6705:
|
||||||
devicePower = vtxRTC6705Pi[sPower];
|
devicePower = vtxRTC6705Pi[sPower];
|
||||||
break;
|
break;
|
||||||
|
#endif // USE_VTX_RTC6705
|
||||||
|
|
||||||
|
#ifdef USE_VTX_SMARTAUDIO
|
||||||
case VTXDEV_SMARTAUDIO:
|
case VTXDEV_SMARTAUDIO:
|
||||||
devicePower = vtxSaPi[sPower];
|
devicePower = vtxSaPi[sPower];
|
||||||
break;
|
break;
|
||||||
|
#endif // USE_VTX_SMARTAUDIO
|
||||||
|
|
||||||
|
#ifdef USE_VTX_TRAMP
|
||||||
case VTXDEV_TRAMP:
|
case VTXDEV_TRAMP:
|
||||||
devicePower = vtxTrampPi[sPower];
|
devicePower = vtxTrampPi[sPower];
|
||||||
break;
|
break;
|
||||||
|
#endif // USE_VTX_TRAMP
|
||||||
|
|
||||||
case VTXDEV_UNKNOWN:
|
case VTXDEV_UNKNOWN:
|
||||||
case VTXDEV_UNSUPPORTED:
|
case VTXDEV_UNSUPPORTED:
|
||||||
|
@ -116,59 +128,71 @@ uint8_t convertSpektrumVtxPowerIndex(uint8_t sPower)
|
||||||
return devicePower;
|
return devicePower;
|
||||||
}
|
}
|
||||||
|
|
||||||
void spektrumHandleVtxControl(uint32_t vtxControl)
|
// Mark an inital invalid VTX ctrl frame to force first VTX settings cheange to actually come from Tx/Rx.
|
||||||
{
|
static uint32_t vtxControl_ipc = ~(SPEKTRUM_VTX_CONTROL_FRAME);
|
||||||
stru_vtx vtx;
|
|
||||||
|
|
||||||
vtx.pitMode = (vtxControl & SPEKTRUM_VTX_PIT_MODE_MASK) >> SPEKTRUM_VTX_PIT_MODE_SHIFT;;
|
// ############ RX task ######################
|
||||||
vtx.region = (vtxControl & SPEKTRUM_VTX_REGION_MASK) >> SPEKTRUM_VTX_REGION_SHIFT;
|
void spektrumHandleVtxControl(uint32_t vtxCntrl)
|
||||||
vtx.power = (vtxControl & SPEKTRUM_VTX_POWER_MASK) >> SPEKTRUM_VTX_POWER_SHIFT;
|
{
|
||||||
vtx.band = (vtxControl & SPEKTRUM_VTX_BAND_MASK) >> SPEKTRUM_VTX_BAND_SHIFT;
|
vtxControl_ipc = vtxCntrl;
|
||||||
vtx.channel = (vtxControl & SPEKTRUM_VTX_CHANNEL_MASK) >> SPEKTRUM_VTX_CHANNEL_SHIFT;
|
}
|
||||||
|
// ###########################################
|
||||||
|
|
||||||
|
|
||||||
|
// ############ VTX_CONTROL task #############
|
||||||
|
void spektrumVtxControl(void)
|
||||||
|
{
|
||||||
|
// Check for invalid VTX ctrl frames
|
||||||
|
if ((vtxControl_ipc & SPEKTRUM_VTX_CONTROL_FRAME_MASK) != SPEKTRUM_VTX_CONTROL_FRAME) return;
|
||||||
|
|
||||||
|
uint32_t vtxControl = vtxControl_ipc;
|
||||||
|
|
||||||
|
spektrumVtx_t vtx = {
|
||||||
|
.pitMode = (vtxControl & SPEKTRUM_VTX_PIT_MODE_MASK) >> SPEKTRUM_VTX_PIT_MODE_SHIFT,
|
||||||
|
.region = (vtxControl & SPEKTRUM_VTX_REGION_MASK) >> SPEKTRUM_VTX_REGION_SHIFT,
|
||||||
|
.power = (vtxControl & SPEKTRUM_VTX_POWER_MASK) >> SPEKTRUM_VTX_POWER_SHIFT,
|
||||||
|
.band = (vtxControl & SPEKTRUM_VTX_BAND_MASK) >> SPEKTRUM_VTX_BAND_SHIFT,
|
||||||
|
.channel = (vtxControl & SPEKTRUM_VTX_CHANNEL_MASK) >> SPEKTRUM_VTX_CHANNEL_SHIFT,
|
||||||
|
};
|
||||||
|
|
||||||
const vtxSettingsConfig_t prevSettings = {
|
const vtxSettingsConfig_t prevSettings = {
|
||||||
.band = vtxSettingsConfig()->band,
|
.band = vtxSettingsConfig()->band,
|
||||||
.channel = vtxSettingsConfig()->channel,
|
.channel = vtxSettingsConfig()->channel,
|
||||||
.freq = vtxSettingsConfig()->freq,
|
.freq = vtxSettingsConfig()->freq,
|
||||||
.power = vtxSettingsConfig()->power,
|
.power = vtxSettingsConfig()->power,
|
||||||
.lowPowerDisarm = vtxSettingsConfig()->lowPowerDisarm,
|
.lowPowerDisarm = vtxSettingsConfig()->lowPowerDisarm,
|
||||||
};
|
};
|
||||||
vtxSettingsConfig_t newSettings = prevSettings;
|
vtxSettingsConfig_t newSettings = prevSettings;
|
||||||
|
|
||||||
#ifdef USE_VTX_COMMON_FREQ_API
|
|
||||||
uint16_t freq = SpektrumVtxfrequencyTable[vtx.band][vtx.channel];
|
|
||||||
if (vtxCommonDeviceRegistered()) {
|
if (vtxCommonDeviceRegistered()) {
|
||||||
|
|
||||||
|
#ifdef USE_VTX_COMMON_FREQ_API
|
||||||
|
uint16_t freq = SpektrumVtxfrequencyTable[vtx.band][vtx.channel];
|
||||||
if (prevSettings.freq != freq) {
|
if (prevSettings.freq != freq) {
|
||||||
newSettings.band = VTX_COMMON_BAND_USER;
|
newSettings.band = VTX_COMMON_BAND_USER;
|
||||||
newSettings.channel = vtx.channel;
|
newSettings.channel = vtx.channel;
|
||||||
newSettings.freq = freq;
|
newSettings.freq = freq;
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
|
||||||
#else
|
#else
|
||||||
// Convert to the internal Common Band index
|
// Convert to the internal Common Band index
|
||||||
uint8_t band = spek2commonBand[vtx.band];
|
uint8_t band = spek2commonBand[vtx.band];
|
||||||
uint8_t channel = vtx.channel +1; // 0 based to 1 based
|
uint8_t channel = vtx.channel +1; // 0 based to 1 based
|
||||||
if (vtxCommonDeviceRegistered()) {
|
|
||||||
if ((prevSettings.band != band) || (prevSettings.channel != channel)) {
|
if ((prevSettings.band != band) || (prevSettings.channel != channel)) {
|
||||||
newSettings.band = band;
|
newSettings.band = band;
|
||||||
newSettings.channel = channel;
|
newSettings.channel = channel;
|
||||||
newSettings.freq = vtx58_Bandchan2Freq(band, channel);
|
newSettings.freq = vtx58_Bandchan2Freq(band, channel);
|
||||||
}
|
}
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Seems to be no unified internal VTX API std for popwer levels/indexes, VTX device brand specific.
|
// Seems to be no unified internal VTX API std for popwer levels/indexes, VTX device brand specific.
|
||||||
uint8_t power = convertSpektrumVtxPowerIndex(vtx.power);
|
uint8_t power = convertSpektrumVtxPowerIndex(vtx.power);
|
||||||
if (vtxCommonDeviceRegistered()) {
|
|
||||||
if (prevSettings.power != power) {
|
if (prevSettings.power != power) {
|
||||||
newSettings.power = power;
|
newSettings.power = power;
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
|
||||||
// Everyone seems to agree on what PIT ON/OFF means
|
// Everyone seems to agree on what PIT ON/OFF means
|
||||||
uint8_t currentPitMode = 0;
|
uint8_t currentPitMode = 0;
|
||||||
if (vtxCommonDeviceRegistered()) {
|
|
||||||
vtxCommonGetPitMode(¤tPitMode);
|
vtxCommonGetPitMode(¤tPitMode);
|
||||||
if (currentPitMode != vtx.pitMode) {
|
if (currentPitMode != vtx.pitMode) {
|
||||||
vtxCommonSetPitMode(vtx.pitMode);
|
vtxCommonSetPitMode(vtx.pitMode);
|
||||||
|
@ -176,10 +200,10 @@ void spektrumHandleVtxControl(uint32_t vtxControl)
|
||||||
}
|
}
|
||||||
|
|
||||||
if(memcmp(&prevSettings,&newSettings,sizeof(vtxSettingsConfig_t))) {
|
if(memcmp(&prevSettings,&newSettings,sizeof(vtxSettingsConfig_t))) {
|
||||||
vtxSettingsConfigMutable()->band = newSettings.band;
|
vtxSettingsConfigMutable()->band = newSettings.band;
|
||||||
vtxSettingsConfigMutable()->channel = newSettings.channel;
|
vtxSettingsConfigMutable()->channel = newSettings.channel;
|
||||||
vtxSettingsConfigMutable()->power = newSettings.power;
|
vtxSettingsConfigMutable()->power = newSettings.power;
|
||||||
vtxSettingsConfigMutable()->freq = newSettings.freq;
|
vtxSettingsConfigMutable()->freq = newSettings.freq;
|
||||||
saveConfigAndNotify();
|
saveConfigAndNotify();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -82,9 +82,11 @@ typedef struct
|
||||||
uint8_t power;
|
uint8_t power;
|
||||||
uint8_t region;
|
uint8_t region;
|
||||||
uint8_t pitMode;
|
uint8_t pitMode;
|
||||||
} stru_vtx;
|
} spektrumVtx_t;
|
||||||
|
|
||||||
|
|
||||||
void spektrumHandleVtxControl(uint32_t vtxControl);
|
void spektrumHandleVtxControl(uint32_t vtxControl);
|
||||||
|
void spektrumVtxControl(void);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -36,6 +36,7 @@
|
||||||
|
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
#include "io/vtx_string.h"
|
#include "io/vtx_string.h"
|
||||||
|
#include "io/vtx_control.h"
|
||||||
|
|
||||||
#include "interface/cli.h"
|
#include "interface/cli.h"
|
||||||
|
|
||||||
|
@ -208,6 +209,9 @@ void vtxUpdate(timeUs_t currentTimeUs)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Check input sources for config updates
|
||||||
|
vtxControlInputPoll();
|
||||||
|
|
||||||
if (vtxCommonDeviceRegistered()) {
|
if (vtxCommonDeviceRegistered()) {
|
||||||
bool vtxUpdatePending = false;
|
bool vtxUpdatePending = false;
|
||||||
const vtxSettingsConfig_t settings = vtxGetSettings();
|
const vtxSettingsConfig_t settings = vtxGetSettings();
|
||||||
|
|
|
@ -37,11 +37,12 @@
|
||||||
#include "fc/config.h"
|
#include "fc/config.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "io/beeper.h"
|
|
||||||
#include "io/osd.h"
|
#include "io/osd.h"
|
||||||
#include "io/vtx_control.h"
|
#include "io/vtx_control.h"
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
|
|
||||||
|
#include "io/spektrum_vtx_control.h"
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
PG_REGISTER_WITH_RESET_TEMPLATE(vtxConfig_t, vtxConfig, PG_VTX_CONFIG, 1);
|
PG_REGISTER_WITH_RESET_TEMPLATE(vtxConfig_t, vtxConfig, PG_VTX_CONFIG, 1);
|
||||||
|
@ -58,6 +59,15 @@ void vtxControlInit(void)
|
||||||
// NOTHING TO DO
|
// NOTHING TO DO
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void vtxControlInputPoll(void)
|
||||||
|
{
|
||||||
|
// Check variuos input sources for VTX config updates
|
||||||
|
#if defined(USE_SPEKTRUM_VTX_CONTROL)
|
||||||
|
// Get VTX updates
|
||||||
|
spektrumVtxControl();
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
static void vtxUpdateBandAndChannel(uint8_t bandStep, uint8_t channelStep)
|
static void vtxUpdateBandAndChannel(uint8_t bandStep, uint8_t channelStep)
|
||||||
{
|
{
|
||||||
if (ARMING_FLAG(ARMED)) {
|
if (ARMING_FLAG(ARMED)) {
|
||||||
|
|
|
@ -42,6 +42,7 @@ typedef struct vtxConfig_s {
|
||||||
PG_DECLARE(vtxConfig_t, vtxConfig);
|
PG_DECLARE(vtxConfig_t, vtxConfig);
|
||||||
|
|
||||||
void vtxControlInit(void);
|
void vtxControlInit(void);
|
||||||
|
void vtxControlInputPoll(void);
|
||||||
|
|
||||||
void vtxIncrementBand(void);
|
void vtxIncrementBand(void);
|
||||||
void vtxDecrementBand(void);
|
void vtxDecrementBand(void);
|
||||||
|
|
|
@ -93,6 +93,7 @@ static void spektrumDataReceive(uint16_t c, void *data)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
uint32_t spekChannelData[SPEKTRUM_MAX_SUPPORTED_CHANNEL_COUNT];
|
uint32_t spekChannelData[SPEKTRUM_MAX_SUPPORTED_CHANNEL_COUNT];
|
||||||
static dispatchEntry_t srxlTelemetryDispatch = { .dispatch = srxlRxSendTelemetryDataDispatch};
|
static dispatchEntry_t srxlTelemetryDispatch = { .dispatch = srxlRxSendTelemetryDataDispatch};
|
||||||
|
|
||||||
|
@ -129,7 +130,7 @@ static uint8_t spektrumFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
|
||||||
(spekFrame[SPEKTRUM_VTX_CONTROL_4] << 0) );
|
(spekFrame[SPEKTRUM_VTX_CONTROL_4] << 0) );
|
||||||
|
|
||||||
// Handle VTX control frame,
|
// Handle VTX control frame,
|
||||||
if ( (vtxControl & SPEKTRUM_VTX_CONTROL_FRAME_MASK) == SPEKTRUM_VTX_CONTROL_FRAME ) {
|
if ((vtxControl & SPEKTRUM_VTX_CONTROL_FRAME_MASK) == SPEKTRUM_VTX_CONTROL_FRAME) {
|
||||||
spektrumHandleVtxControl(vtxControl);
|
spektrumHandleVtxControl(vtxControl);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue