Merge pull request #4777 from AndersHoglund/split_spektrum_vtx_control
Moved Spektrum VTX control stuff to separate source files.
This commit is contained in:
commit
3e2ade8565
|
@ -115,6 +115,7 @@ FC_SRC = \
|
|||
rx/sbus.c \
|
||||
rx/sbus_channels.c \
|
||||
rx/spektrum.c \
|
||||
io/spektrum_vtx_control.c \
|
||||
rx/sumd.c \
|
||||
rx/sumh.c \
|
||||
rx/xbus.c \
|
||||
|
|
|
@ -0,0 +1,187 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it 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 is distributed in the hope that it 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
|
||||
#include "platform.h"
|
||||
#if defined(USE_SPEKTRUM_VTX_CONTROL) && defined(VTX_COMMON)
|
||||
|
||||
#include <string.h>
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "drivers/vtx_common.h"
|
||||
#include "io/vtx.h"
|
||||
#include "io/vtx_string.h"
|
||||
|
||||
#include "io/spektrum_vtx_control.h"
|
||||
|
||||
// We can not use the common set/get-frequncy API.
|
||||
// Some VTX devices do not support it.
|
||||
//#define USE_VTX_COMMON_FREQ_API
|
||||
|
||||
#ifdef USE_VTX_COMMON_FREQ_API
|
||||
const uint16_t SpektrumVtxfrequencyTable[SPEKTRUM_VTX_BAND_COUNT][SPEKTRUM_VTX_CHAN_COUNT] =
|
||||
{
|
||||
{ 5740, 5760, 5780, 5800, 5820, 5840, 5860, 5880 }, // FatShark
|
||||
{ 5658, 5695, 5732, 5769, 5806, 5843, 5880, 5917 }, // RaceBand
|
||||
{ 5705, 5685, 5665, 5645, 5885, 5905, 5925, 5945 }, // Boscam E
|
||||
{ 5733, 5752, 5771, 5790, 5809, 5828, 5847, 5866 }, // Boscam B
|
||||
{ 5865, 5845, 5825, 5805, 5785, 5765, 5745, 5725 }, // Boscam A
|
||||
};
|
||||
#else
|
||||
// Translation table, Spektrum bands to BF internal vtx_common bands
|
||||
const uint8_t spek2commonBand[]= {
|
||||
VTX_COMMON_BAND_FS,
|
||||
VTX_COMMON_BAND_RACE,
|
||||
VTX_COMMON_BAND_E,
|
||||
VTX_COMMON_BAND_B,
|
||||
VTX_COMMON_BAND_A,
|
||||
};
|
||||
#endif
|
||||
|
||||
// RF Power Index translation tables. No generic power API available.....
|
||||
|
||||
// Tramp "---", 25, 200, 400. 600 mW
|
||||
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, // 1 - 14mW - - - -
|
||||
VTX_TRAMP_POWER_25, // 15 - 25mW 15 - 25mW 2 1 25mW
|
||||
VTX_TRAMP_POWER_100, // 26 - 99mW 26 - 99mW 3 2 100mW Slightly outside range
|
||||
VTX_TRAMP_POWER_200, // 100 - 299mW 100 - 200mW 4 3 200mW
|
||||
VTX_TRAMP_POWER_400, // 300 - 600mW 300 - 600mW 5 4 400mW
|
||||
VTX_TRAMP_POWER_600, // 601 - max 601+ mW 6 5 600mW Slightly outside range
|
||||
VTX_TRAMP_POWER_200 // Manual - - - -
|
||||
};
|
||||
|
||||
// RTC6705 "---", 25 or 200 mW
|
||||
const uint8_t vtxRTC6705Pi[] = {
|
||||
VTX_6705_POWER_OFF, // Off
|
||||
VTX_6705_POWER_OFF, // 1 - 14mW
|
||||
VTX_6705_POWER_25, // 15 - 25mW
|
||||
VTX_6705_POWER_25, // 26 - 99mW
|
||||
VTX_6705_POWER_200, // 100 - 299mW
|
||||
VTX_6705_POWER_200, // 300 - 600mW
|
||||
VTX_6705_POWER_200, // 601 - max
|
||||
VTX_6705_POWER_200 // Manual
|
||||
};
|
||||
|
||||
// SmartAudio "---", 25, 200, 500. 800 mW
|
||||
const uint8_t vtxSaPi[] = {
|
||||
VTX_SA_POWER_OFF, // Off
|
||||
VTX_SA_POWER_OFF, // 1 - 14mW
|
||||
VTX_SA_POWER_25, // 15 - 25mW
|
||||
VTX_SA_POWER_25, // 26 - 99mW
|
||||
VTX_SA_POWER_200, // 100 - 299mW
|
||||
VTX_SA_POWER_500, // 300 - 600mW
|
||||
VTX_SA_POWER_800, // 601 - max
|
||||
VTX_SA_POWER_200 // Manual
|
||||
};
|
||||
|
||||
uint8_t convertSpektrumVtxPowerIndex(uint8_t sPower)
|
||||
{
|
||||
uint8_t devicePower = 0;
|
||||
|
||||
switch (vtxCommonGetDeviceType()) {
|
||||
case VTXDEV_RTC6705:
|
||||
devicePower = vtxRTC6705Pi[sPower];
|
||||
break;
|
||||
|
||||
case VTXDEV_SMARTAUDIO:
|
||||
devicePower = vtxSaPi[sPower];
|
||||
break;
|
||||
|
||||
case VTXDEV_TRAMP:
|
||||
devicePower = vtxTrampPi[sPower];
|
||||
break;
|
||||
|
||||
case VTXDEV_UNKNOWN:
|
||||
case VTXDEV_UNSUPPORTED:
|
||||
default:
|
||||
break;
|
||||
|
||||
}
|
||||
return devicePower;
|
||||
}
|
||||
|
||||
void spektrumHandleVtxControl(uint32_t vtxControl)
|
||||
{
|
||||
stru_vtx vtx;
|
||||
|
||||
vtx.pitMode = (vtxControl & SPEKTRUM_VTX_PIT_MODE_MASK) >> SPEKTRUM_VTX_PIT_MODE_SHIFT;;
|
||||
vtx.region = (vtxControl & SPEKTRUM_VTX_REGION_MASK) >> SPEKTRUM_VTX_REGION_SHIFT;
|
||||
vtx.power = (vtxControl & SPEKTRUM_VTX_POWER_MASK) >> SPEKTRUM_VTX_POWER_SHIFT;
|
||||
vtx.band = (vtxControl & SPEKTRUM_VTX_BAND_MASK) >> SPEKTRUM_VTX_BAND_SHIFT;
|
||||
vtx.channel = (vtxControl & SPEKTRUM_VTX_CHANNEL_MASK) >> SPEKTRUM_VTX_CHANNEL_SHIFT;
|
||||
|
||||
const vtxSettingsConfig_t prevSettings = {
|
||||
.band = vtxSettingsConfig()->band,
|
||||
.channel = vtxSettingsConfig()->channel,
|
||||
.freq = vtxSettingsConfig()->freq,
|
||||
.power = vtxSettingsConfig()->power,
|
||||
.lowPowerDisarm = vtxSettingsConfig()->lowPowerDisarm,
|
||||
};
|
||||
vtxSettingsConfig_t newSettings = prevSettings;
|
||||
|
||||
#ifdef USE_VTX_COMMON_FREQ_API
|
||||
uint16_t freq = SpektrumVtxfrequencyTable[vtx.band][vtx.channel];
|
||||
if (vtxCommonDeviceRegistered()) {
|
||||
if (prevSettings.freq != freq) {
|
||||
newSettings.band = VTX_COMMON_BAND_USER;
|
||||
newSettings.channel = vtx.channel;
|
||||
newSettings.freq = freq;
|
||||
}
|
||||
}
|
||||
|
||||
#else
|
||||
// Convert to the internal Common Band index
|
||||
uint8_t band = spek2commonBand[vtx.band];
|
||||
uint8_t channel = vtx.channel +1; // 0 based to 1 based
|
||||
if (vtxCommonDeviceRegistered()) {
|
||||
if ((prevSettings.band != band) || (prevSettings.channel != channel)) {
|
||||
newSettings.band = band;
|
||||
newSettings.channel = channel;
|
||||
newSettings.freq = vtx58_Bandchan2Freq(band, channel);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
// Seems to be no unified internal VTX API std for popwer levels/indexes, VTX device brand specific.
|
||||
uint8_t power = convertSpektrumVtxPowerIndex(vtx.power);
|
||||
if (vtxCommonDeviceRegistered()) {
|
||||
if (prevSettings.power != power) {
|
||||
newSettings.power = power;
|
||||
}
|
||||
}
|
||||
|
||||
// Everyone seems to agree on what PIT ON/OFF means
|
||||
uint8_t currentPitMode = 0;
|
||||
if (vtxCommonDeviceRegistered()) {
|
||||
vtxCommonGetPitMode(¤tPitMode);
|
||||
if (currentPitMode != vtx.pitMode) {
|
||||
vtxCommonSetPitMode(vtx.pitMode);
|
||||
}
|
||||
}
|
||||
|
||||
if(memcmp(&prevSettings,&newSettings,sizeof(vtxSettingsConfig_t))) {
|
||||
vtxSettingsConfigMutable()->band = newSettings.band;
|
||||
vtxSettingsConfigMutable()->channel = newSettings.channel;
|
||||
vtxSettingsConfigMutable()->power = newSettings.power;
|
||||
vtxSettingsConfigMutable()->freq = newSettings.freq;
|
||||
saveConfigAndNotify();
|
||||
}
|
||||
}
|
||||
|
||||
#endif // USE_SPEKTRUM_VTX_CONTROL && VTX_COMMON
|
|
@ -0,0 +1,90 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it 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 is distributed in the hope that it 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
|
||||
|
||||
//VTX control frame bits and pieces
|
||||
#define SPEKTRUM_VTX_CONTROL_FRAME_MASK 0xf000f000
|
||||
#define SPEKTRUM_VTX_CONTROL_FRAME 0xe000e000
|
||||
|
||||
#define SPEKTRUM_VTX_CONTROL_1 (SPEK_FRAME_SIZE - 4)
|
||||
#define SPEKTRUM_VTX_CONTROL_2 (SPEK_FRAME_SIZE - 3)
|
||||
#define SPEKTRUM_VTX_CONTROL_3 (SPEK_FRAME_SIZE - 2)
|
||||
#define SPEKTRUM_VTX_CONTROL_4 (SPEK_FRAME_SIZE - 1)
|
||||
|
||||
#define SPEKTRUM_VTX_BAND_MASK 0x00e00000
|
||||
#define SPEKTRUM_VTX_CHANNEL_MASK 0x000f0000
|
||||
#define SPEKTRUM_VTX_PIT_MODE_MASK 0x00000010
|
||||
#define SPEKTRUM_VTX_REGION_MASK 0x00000008
|
||||
#define SPEKTRUM_VTX_POWER_MASK 0x00000007
|
||||
|
||||
#define SPEKTRUM_VTX_BAND_SHIFT 21
|
||||
#define SPEKTRUM_VTX_CHANNEL_SHIFT 16
|
||||
#define SPEKTRUM_VTX_PIT_MODE_SHIFT 4
|
||||
#define SPEKTRUM_VTX_REGION_SHIFT 3
|
||||
#define SPEKTRUM_VTX_POWER_SHIFT 0
|
||||
|
||||
#define SPEKTRUM_VTX_BAND_COUNT 5
|
||||
#define SPEKTRUM_VTX_CHAN_COUNT 8
|
||||
|
||||
/*
|
||||
Channels vs Band according to spektrum spec.
|
||||
0 1 2 3 4 5 6 7
|
||||
5740 5760 5780 5800 5820 5840 5860 5880 FatShark
|
||||
5658 5695 5732 5769 5806 5843 5880 5917 Race
|
||||
5705 5685 5665 5645 5885 5905 5925 5945 Band E
|
||||
5733 5752 5771 5790 5809 5828 5847 5866 Band B
|
||||
5865 5845 5825 5805 5785 5765 5745 5725 Band A
|
||||
*/
|
||||
|
||||
// Band translation to BF internal vtx_common needed
|
||||
// Spektrum order, zero based.
|
||||
#define SPEKTRUM_VTX_BAND_FS 0
|
||||
#define SPEKTRUM_VTX_BAND_RACE 1
|
||||
#define SPEKTRUM_VTX_BAND_E 2
|
||||
#define SPEKTRUM_VTX_BAND_B 3
|
||||
#define SPEKTRUM_VTX_BAND_A 4
|
||||
|
||||
// Spektrum Max power index
|
||||
#define SPEKTRUM_VTX_POWER_OFF 0
|
||||
#define SPEKTRUM_VTX_POWER_14 1
|
||||
#define SPEKTRUM_VTX_POWER_25 2
|
||||
#define SPEKTRUM_VTX_POWER_99 3
|
||||
#define SPEKTRUM_VTX_POWER_299 4
|
||||
#define SPEKTRUM_VTX_POWER_600 5
|
||||
#define SPEKTRUM_VTX_POWER_MAXIT 6
|
||||
#define SPEKTRUM_VTX_POWER_MAN 7
|
||||
|
||||
#define SPEKTRUM_VTX_REGION_USA 0
|
||||
#define SPEKTRUM_VTX_REGION_EU 1
|
||||
|
||||
#define SPEKTRUM_VTX_PITMODE_OFF 0 // Power on, race
|
||||
#define SPEKTRUM_VTX_PITMODE_ON 1 // Power off, pit
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t band;
|
||||
uint8_t channel;
|
||||
uint8_t power;
|
||||
uint8_t region;
|
||||
uint8_t pitMode;
|
||||
} stru_vtx;
|
||||
|
||||
void spektrumHandleVtxControl(uint32_t vtxControl);
|
||||
|
||||
|
||||
|
|
@ -15,15 +15,13 @@
|
|||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include "string.h"
|
||||
#include "platform.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#ifdef USE_SERIAL_RX
|
||||
|
||||
#include <string.h>
|
||||
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
|
@ -31,15 +29,16 @@
|
|||
#include "drivers/light_led.h"
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/vtx_common.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/vtx.h"
|
||||
#include "io/vtx_string.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/fc_dispatch.h"
|
||||
|
||||
#if defined(USE_SPEKTRUM_VTX_CONTROL) && defined(VTX_COMMON)
|
||||
#include "io/spektrum_vtx_control.h"
|
||||
#endif
|
||||
|
||||
#ifdef USE_TELEMETRY
|
||||
#include "telemetry/telemetry.h"
|
||||
#endif
|
||||
|
@ -161,166 +160,6 @@ static int8_t dBm2range (int8_t dBm)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if defined(USE_SPEKTRUM_VTX_CONTROL) && defined(VTX_COMMON)
|
||||
|
||||
// We can not use the common set/get-frequncy API.
|
||||
// Some VTX devices do not support it.
|
||||
//#define USE_VTX_COMMON_FREQ_API
|
||||
|
||||
#ifdef USE_VTX_COMMON_FREQ_API
|
||||
const uint16_t SpektrumVtxfrequencyTable[SPEKTRUM_VTX_BAND_COUNT][SPEKTRUM_VTX_CHAN_COUNT] =
|
||||
{
|
||||
{ 5740, 5760, 5780, 5800, 5820, 5840, 5860, 5880 }, // FatShark
|
||||
{ 5658, 5695, 5732, 5769, 5806, 5843, 5880, 5917 }, // RaceBand
|
||||
{ 5705, 5685, 5665, 5645, 5885, 5905, 5925, 5945 }, // Boscam E
|
||||
{ 5733, 5752, 5771, 5790, 5809, 5828, 5847, 5866 }, // Boscam B
|
||||
{ 5865, 5845, 5825, 5805, 5785, 5765, 5745, 5725 }, // Boscam A
|
||||
};
|
||||
#else
|
||||
// Translation table, Spektrum bands to BF internal vtx_common bands
|
||||
const uint8_t spek2commonBand[]= {
|
||||
VTX_COMMON_BAND_FS,
|
||||
VTX_COMMON_BAND_RACE,
|
||||
VTX_COMMON_BAND_E,
|
||||
VTX_COMMON_BAND_B,
|
||||
VTX_COMMON_BAND_A,
|
||||
};
|
||||
#endif
|
||||
|
||||
// RF Power Index translation tables. No generic power API available.....
|
||||
|
||||
// Tramp "---", 25, 200, 400. 600 mW
|
||||
const uint8_t vtxTrampPi[] = { // Spektrum Spec Tx menu Tx sends To VTX Wand
|
||||
VTX_TRAMP_POWER_OFF, // Off INHIBIT 0 0 -
|
||||
VTX_TRAMP_POWER_OFF, // 1 - 14mW - - - -
|
||||
VTX_TRAMP_POWER_25, // 15 - 25mW 15 - 25mW 2 1 25mW
|
||||
VTX_TRAMP_POWER_100, // 26 - 99mW 26 - 99mW 3 2 100mW Slightly outside range
|
||||
VTX_TRAMP_POWER_200, // 100 - 299mW 100 - 200mW 4 3 200mW
|
||||
VTX_TRAMP_POWER_400, // 300 - 600mW 300 - 600mW 5 4 400mW
|
||||
VTX_TRAMP_POWER_600, // 601 - max 601+ mW 6 5 600mW Slightly outside range
|
||||
VTX_TRAMP_POWER_200 // Manual - - - -
|
||||
};
|
||||
|
||||
// RTC6705 "---", 25 or 200 mW
|
||||
const uint8_t vtxRTC6705Pi[] = {
|
||||
VTX_6705_POWER_OFF, // Off
|
||||
VTX_6705_POWER_OFF, // 1 - 14mW
|
||||
VTX_6705_POWER_25, // 15 - 25mW
|
||||
VTX_6705_POWER_25, // 26 - 99mW
|
||||
VTX_6705_POWER_200, // 100 - 299mW
|
||||
VTX_6705_POWER_200, // 300 - 600mW
|
||||
VTX_6705_POWER_200, // 601 - max
|
||||
VTX_6705_POWER_200 // Manual
|
||||
};
|
||||
|
||||
// SmartAudio "---", 25, 200, 500. 800 mW
|
||||
const uint8_t vtxSaPi[] = {
|
||||
VTX_SA_POWER_OFF, // Off
|
||||
VTX_SA_POWER_OFF, // 1 - 14mW
|
||||
VTX_SA_POWER_25, // 15 - 25mW
|
||||
VTX_SA_POWER_25, // 26 - 99mW
|
||||
VTX_SA_POWER_200, // 100 - 299mW
|
||||
VTX_SA_POWER_500, // 300 - 600mW
|
||||
VTX_SA_POWER_800, // 601 - max
|
||||
VTX_SA_POWER_200 // Manual
|
||||
};
|
||||
|
||||
uint8_t convertSpektrumVtxPowerIndex(uint8_t sPower)
|
||||
{
|
||||
uint8_t devicePower = 0;
|
||||
|
||||
switch (vtxCommonGetDeviceType()) {
|
||||
case VTXDEV_RTC6705:
|
||||
devicePower = vtxRTC6705Pi[sPower];
|
||||
break;
|
||||
|
||||
case VTXDEV_SMARTAUDIO:
|
||||
devicePower = vtxSaPi[sPower];
|
||||
break;
|
||||
|
||||
case VTXDEV_TRAMP:
|
||||
devicePower = vtxTrampPi[sPower];
|
||||
break;
|
||||
|
||||
case VTXDEV_UNKNOWN:
|
||||
case VTXDEV_UNSUPPORTED:
|
||||
default:
|
||||
break;
|
||||
|
||||
}
|
||||
return devicePower;
|
||||
}
|
||||
|
||||
void handleSpektrumVtxControl(uint32_t vtxControl)
|
||||
{
|
||||
stru_vtx vtx;
|
||||
|
||||
vtx.pitMode = (vtxControl & SPEKTRUM_VTX_PIT_MODE_MASK) >> SPEKTRUM_VTX_PIT_MODE_SHIFT;;
|
||||
vtx.region = (vtxControl & SPEKTRUM_VTX_REGION_MASK) >> SPEKTRUM_VTX_REGION_SHIFT;
|
||||
vtx.power = (vtxControl & SPEKTRUM_VTX_POWER_MASK) >> SPEKTRUM_VTX_POWER_SHIFT;
|
||||
vtx.band = (vtxControl & SPEKTRUM_VTX_BAND_MASK) >> SPEKTRUM_VTX_BAND_SHIFT;
|
||||
vtx.channel = (vtxControl & SPEKTRUM_VTX_CHANNEL_MASK) >> SPEKTRUM_VTX_CHANNEL_SHIFT;
|
||||
|
||||
const vtxSettingsConfig_t prevSettings = {
|
||||
.band = vtxSettingsConfig()->band,
|
||||
.channel = vtxSettingsConfig()->channel,
|
||||
.freq = vtxSettingsConfig()->freq,
|
||||
.power = vtxSettingsConfig()->power,
|
||||
.lowPowerDisarm = vtxSettingsConfig()->lowPowerDisarm,
|
||||
};
|
||||
vtxSettingsConfig_t newSettings = prevSettings;
|
||||
|
||||
#ifdef USE_VTX_COMMON_FREQ_API
|
||||
uint16_t freq = SpektrumVtxfrequencyTable[vtx.band][vtx.channel];
|
||||
if (vtxCommonDeviceRegistered()) {
|
||||
if (prevSettings.freq != freq) {
|
||||
newSettings.band = VTX_COMMON_BAND_USER;
|
||||
newSettings.channel = vtx.channel;
|
||||
newSettings.freq = freq;
|
||||
}
|
||||
}
|
||||
|
||||
#else
|
||||
// Convert to the internal Common Band index
|
||||
uint8_t band = spek2commonBand[vtx.band];
|
||||
uint8_t channel = vtx.channel +1; // 0 based to 1 based
|
||||
if (vtxCommonDeviceRegistered()) {
|
||||
if ((prevSettings.band != band) || (prevSettings.channel != channel)) {
|
||||
newSettings.band = band;
|
||||
newSettings.channel = channel;
|
||||
newSettings.freq = vtx58_Bandchan2Freq(band, channel);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
// Seems to be no unified internal VTX API std for popwer levels/indexes, VTX device brand specific.
|
||||
uint8_t power = convertSpektrumVtxPowerIndex(vtx.power);
|
||||
if (vtxCommonDeviceRegistered()) {
|
||||
if (prevSettings.power != power) {
|
||||
newSettings.power = power;
|
||||
}
|
||||
}
|
||||
|
||||
// Everyone seems to agree on what PIT ON/OFF means
|
||||
uint8_t currentPitMode = 0;
|
||||
if (vtxCommonDeviceRegistered()) {
|
||||
vtxCommonGetPitMode(¤tPitMode);
|
||||
if (currentPitMode != vtx.pitMode) {
|
||||
vtxCommonSetPitMode(vtx.pitMode);
|
||||
}
|
||||
}
|
||||
|
||||
if(memcmp(&prevSettings,&newSettings,sizeof(vtxSettingsConfig_t))) {
|
||||
vtxSettingsConfigMutable()->band = newSettings.band;
|
||||
vtxSettingsConfigMutable()->channel = newSettings.channel;
|
||||
vtxSettingsConfigMutable()->power = newSettings.power;
|
||||
vtxSettingsConfigMutable()->freq = newSettings.freq;
|
||||
saveConfigAndNotify();
|
||||
}
|
||||
}
|
||||
|
||||
#endif // USE_SPEKTRUM_VTX_CONTROL && VTX_COMMON
|
||||
|
||||
|
||||
// Receive ISR callback
|
||||
static void spektrumDataReceive(uint16_t c, void *data)
|
||||
|
@ -469,9 +308,9 @@ static uint8_t spektrumFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
|
|||
(spekFrame[SPEKTRUM_VTX_CONTROL_3] << 8) |
|
||||
(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 ) {
|
||||
handleSpektrumVtxControl(vtxControl);
|
||||
spektrumHandleVtxControl(vtxControl);
|
||||
}
|
||||
|
||||
#endif // USE_SPEKTRUM_VTX_CONTROL && VTX_COMMON
|
||||
|
|
|
@ -44,73 +44,6 @@ typedef struct
|
|||
} stru_dbm_table;
|
||||
|
||||
|
||||
//VTX control frame bits and pieces
|
||||
#define SPEKTRUM_VTX_CONTROL_FRAME_MASK 0xf000f000
|
||||
#define SPEKTRUM_VTX_CONTROL_FRAME 0xe000e000
|
||||
|
||||
#define SPEKTRUM_VTX_CONTROL_1 (SPEK_FRAME_SIZE - 4)
|
||||
#define SPEKTRUM_VTX_CONTROL_2 (SPEK_FRAME_SIZE - 3)
|
||||
#define SPEKTRUM_VTX_CONTROL_3 (SPEK_FRAME_SIZE - 2)
|
||||
#define SPEKTRUM_VTX_CONTROL_4 (SPEK_FRAME_SIZE - 1)
|
||||
|
||||
#define SPEKTRUM_VTX_BAND_MASK 0x00e00000
|
||||
#define SPEKTRUM_VTX_CHANNEL_MASK 0x000f0000
|
||||
#define SPEKTRUM_VTX_PIT_MODE_MASK 0x00000010
|
||||
#define SPEKTRUM_VTX_REGION_MASK 0x00000008
|
||||
#define SPEKTRUM_VTX_POWER_MASK 0x00000007
|
||||
|
||||
#define SPEKTRUM_VTX_BAND_SHIFT 21
|
||||
#define SPEKTRUM_VTX_CHANNEL_SHIFT 16
|
||||
#define SPEKTRUM_VTX_PIT_MODE_SHIFT 4
|
||||
#define SPEKTRUM_VTX_REGION_SHIFT 3
|
||||
#define SPEKTRUM_VTX_POWER_SHIFT 0
|
||||
|
||||
#define SPEKTRUM_VTX_BAND_COUNT 5
|
||||
#define SPEKTRUM_VTX_CHAN_COUNT 8
|
||||
|
||||
/*
|
||||
Channels vs Band according to spektrum spec.
|
||||
0 1 2 3 4 5 6 7
|
||||
5740 5760 5780 5800 5820 5840 5860 5880 FatShark
|
||||
5658 5695 5732 5769 5806 5843 5880 5917 Race
|
||||
5705 5685 5665 5645 5885 5905 5925 5945 Band E
|
||||
5733 5752 5771 5790 5809 5828 5847 5866 Band B
|
||||
5865 5845 5825 5805 5785 5765 5745 5725 Band A
|
||||
*/
|
||||
|
||||
// Band translation to BF internal vtx_common needed
|
||||
// Spektrum order, zero based.
|
||||
#define SPEKTRUM_VTX_BAND_FS 0
|
||||
#define SPEKTRUM_VTX_BAND_RACE 1
|
||||
#define SPEKTRUM_VTX_BAND_E 2
|
||||
#define SPEKTRUM_VTX_BAND_B 3
|
||||
#define SPEKTRUM_VTX_BAND_A 4
|
||||
|
||||
// Spektrum Max power index
|
||||
#define SPEKTRUM_VTX_POWER_OFF 0
|
||||
#define SPEKTRUM_VTX_POWER_14 1
|
||||
#define SPEKTRUM_VTX_POWER_25 2
|
||||
#define SPEKTRUM_VTX_POWER_99 3
|
||||
#define SPEKTRUM_VTX_POWER_299 4
|
||||
#define SPEKTRUM_VTX_POWER_600 5
|
||||
#define SPEKTRUM_VTX_POWER_MAXIT 6
|
||||
#define SPEKTRUM_VTX_POWER_MAN 7
|
||||
|
||||
#define SPEKTRUM_VTX_REGION_USA 0
|
||||
#define SPEKTRUM_VTX_REGION_EU 1
|
||||
|
||||
#define SPEKTRUM_VTX_PITMODE_OFF 0 // Power on, race
|
||||
#define SPEKTRUM_VTX_PITMODE_ON 1 // Power off, pit
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t band;
|
||||
uint8_t channel;
|
||||
uint8_t power;
|
||||
uint8_t region;
|
||||
uint8_t pitMode;
|
||||
} stru_vtx;
|
||||
|
||||
void spektrumBind(rxConfig_t *rxConfig);
|
||||
bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
|
||||
|
||||
|
|
Loading…
Reference in New Issue