1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-26 17:55:28 +03:00

latest changes for smart audio (copied from Betaflight, various commits)

This commit is contained in:
Stefan Haubold 2017-05-09 08:48:39 +02:00 committed by Pawel Spychalski (DzikuVx)
parent 6cdac94e71
commit 737fa01d87
16 changed files with 895 additions and 152 deletions

View file

@ -661,6 +661,7 @@ HIGHEND_SRC = \
drivers/rangefinder_hcsr04_i2c.c \
drivers/rangefinder_srf10.c \
drivers/rangefinder_vl53l0x.c \
drivers/vtx_common.c \
io/dashboard.c \
io/displayport_max7456.c \
io/displayport_msp.c \
@ -690,9 +691,10 @@ HIGHEND_SRC = \
telemetry/mavlink.c \
telemetry/smartport.c \
telemetry/telemetry.c \
io/vtx_common.c \
io/vtx_string.c \
io/vtx_smartaudio.c \
io/vtx_tramp.c
io/vtx_tramp.c \
io/vtx_control.c
ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS)))
VCP_SRC = \

View file

@ -72,7 +72,7 @@
//#define PG_DEBUG_CONFIG 51
#define PG_SERVO_CONFIG 52
//#define PG_IBUS_TELEMETRY_CONFIG 53
//#define PG_VTX_CONFIG 54
#define PG_VTX_CONFIG 54
#define PG_ELERES_CONFIG 55
#define PG_CF_END 56

View file

@ -0,0 +1,139 @@
/*
* 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/>.
*/
/* Created by jflyper */
#include <stdbool.h>
#include <stdint.h>
#include <ctype.h>
#include <string.h>
#include "platform.h"
#include "build/debug.h"
#if defined(VTX_COMMON)
#include "vtx_common.h"
vtxDevice_t *vtxDevice = NULL;
void vtxCommonInit(void)
{
}
// Whatever registered last will win
void vtxCommonRegisterDevice(vtxDevice_t *pDevice)
{
vtxDevice = pDevice;
}
void vtxCommonProcess(timeUs_t currentTimeUs)
{
if (!vtxDevice)
return;
if (vtxDevice->vTable->process)
vtxDevice->vTable->process(currentTimeUs);
}
vtxDevType_e vtxCommonGetDeviceType(void)
{
if (!vtxDevice || !vtxDevice->vTable->getDeviceType)
return VTXDEV_UNKNOWN;
return vtxDevice->vTable->getDeviceType();
}
// band and channel are 1 origin
void vtxCommonSetBandAndChannel(uint8_t band, uint8_t channel)
{
if (!vtxDevice)
return;
if ((band > vtxDevice->capability.bandCount) || (channel > vtxDevice->capability.channelCount))
return;
if (vtxDevice->vTable->setBandAndChannel)
vtxDevice->vTable->setBandAndChannel(band, channel);
}
// index is zero origin, zero = power off completely
void vtxCommonSetPowerByIndex(uint8_t index)
{
if (!vtxDevice)
return;
if (index > vtxDevice->capability.powerCount)
return;
if (vtxDevice->vTable->setPowerByIndex)
vtxDevice->vTable->setPowerByIndex(index);
}
// on = 1, off = 0
void vtxCommonSetPitMode(uint8_t onoff)
{
if (!vtxDevice)
return;
if (vtxDevice->vTable->setPitMode)
vtxDevice->vTable->setPitMode(onoff);
}
bool vtxCommonGetBandAndChannel(uint8_t *pBand, uint8_t *pChannel)
{
if (!vtxDevice)
return false;
if (vtxDevice->vTable->getBandAndChannel)
return vtxDevice->vTable->getBandAndChannel(pBand, pChannel);
else
return false;
}
bool vtxCommonGetPowerIndex(uint8_t *pIndex)
{
if (!vtxDevice)
return false;
if (vtxDevice->vTable->getPowerIndex)
return vtxDevice->vTable->getPowerIndex(pIndex);
else
return false;
}
bool vtxCommonGetPitMode(uint8_t *pOnOff)
{
if (!vtxDevice)
return false;
if (vtxDevice->vTable->getPitMode)
return vtxDevice->vTable->getPitMode(pOnOff);
else
return false;
}
bool vtxCommonGetDeviceCapability(vtxDeviceCapability_t *pDeviceCapability)
{
if (!vtxDevice)
return false;
memcpy(pDeviceCapability, &vtxDevice->capability, sizeof(vtxDeviceCapability_t));
return true;
}
#endif

View file

@ -0,0 +1,91 @@
/*
* 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/>.
*/
/* Created by jflyper */
#include "common/time.h"
typedef enum {
VTXDEV_UNSUPPORTED = 0, // reserved for MSP
VTXDEV_RTC6705 = 1,
// 2 reserved
VTXDEV_SMARTAUDIO = 3,
VTXDEV_TRAMP = 4,
VTXDEV_UNKNOWN = 0xFF,
} vtxDevType_e;
struct vtxVTable_s;
typedef struct vtxDeviceCapability_s {
uint8_t bandCount;
uint8_t channelCount;
uint8_t powerCount;
} vtxDeviceCapability_t;
typedef struct vtxDevice_s {
const struct vtxVTable_s const *vTable;
vtxDeviceCapability_t capability;
uint16_t *frequencyTable; // Array of [bandCount][channelCount]
char **bandNames; // char *bandNames[bandCount]
char **channelNames; // char *channelNames[channelCount]
char **powerNames; // char *powerNames[powerCount]
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;
// {set,get}BandAndChannel: band and channel are 1 origin
// {set,get}PowerByIndex: 0 = Power OFF, 1 = device dependent
// {set,get}PitMode: 0 = OFF, 1 = ON
typedef struct vtxVTable_s {
void (*process)(uint32_t currentTimeUs);
vtxDevType_e (*getDeviceType)(void);
bool (*isReady)(void);
void (*setBandAndChannel)(uint8_t band, uint8_t channel);
void (*setPowerByIndex)(uint8_t level);
void (*setPitMode)(uint8_t onoff);
bool (*getBandAndChannel)(uint8_t *pBand, uint8_t *pChannel);
bool (*getPowerIndex)(uint8_t *pIndex);
bool (*getPitMode)(uint8_t *pOnOff);
} vtxVTable_t;
// 3.1.0
// PIT mode is defined as LOWEST POSSIBLE RF POWER.
// - It can be a dedicated mode, or lowest RF power possible.
// - It is *NOT* RF on/off control ?
void vtxCommonInit(void);
void vtxCommonRegisterDevice(vtxDevice_t *pDevice);
// VTable functions
void vtxCommonProcess(timeUs_t currentTimeUs);
uint8_t vtxCommonGetDeviceType(void);
void vtxCommonSetBandAndChannel(uint8_t band, uint8_t channel);
void vtxCommonSetPowerByIndex(uint8_t level);
void vtxCommonSetPitMode(uint8_t onoff);
bool vtxCommonGetBandAndChannel(uint8_t *pBand, uint8_t *pChannel);
bool vtxCommonGetPowerIndex(uint8_t *pIndex);
bool vtxCommonGetPitMode(uint8_t *pOnOff);
bool vtxCommonGetDeviceCapability(vtxDeviceCapability_t *pDeviceCapability);

View file

@ -38,7 +38,6 @@
#include "drivers/vtx_rtc6705.h"
#define RTC6705_SET_HEAD 0x3210 //fosc=8mhz r=400
#define RTC6705_SET_A1 0x8F3031 //5865
#define RTC6705_SET_A2 0x8EB1B1 //5845

View file

@ -71,6 +71,12 @@
#include "drivers/time.h"
#include "drivers/timer.h"
#include "drivers/vcd.h"
#include "drivers/gyro_sync.h"
#include "drivers/io.h"
#include "drivers/exti.h"
#include "drivers/io_pca9685.h"
#include "drivers/vtx_rtc6705.h"
#include "drivers/vtx_common.h"
#include "fc/cli.h"
#include "fc/config.h"
@ -99,6 +105,7 @@
#include "io/rcsplit.h"
#include "io/serial.h"
#include "io/displayport_msp.h"
#include "io/vtx_control.h"
#include "io/vtx_smartaudio.h"
#include "io/vtx_tramp.h"
@ -628,13 +635,16 @@ void init(void)
#endif
#ifdef VTX_CONTROL
vtxControlInit();
vtxCommonInit();
#ifdef VTX_SMARTAUDIO
smartAudioInit();
vtxSmartAudioInit();
#endif
#ifdef VTX_TRAMP
trampInit();
vtxTrampInit();
#endif
#endif // VTX_CONTROL

View file

@ -32,6 +32,7 @@
#include "drivers/sensor.h"
#include "drivers/serial.h"
#include "drivers/stack_check.h"
#include "drivers/vtx_common.h"
#include "fc/cli.h"
#include "fc/config.h"
@ -55,8 +56,6 @@
#include "io/pwmdriver_i2c.h"
#include "io/serial.h"
#include "io/rcsplit.h"
#include "io/vtx_smartaudio.h"
#include "io/vtx_tramp.h"
#include "msp/msp_serial.h"
@ -266,11 +265,8 @@ void taskVtxControl(timeUs_t currentTimeUs)
if (ARMING_FLAG(ARMED))
return;
#ifdef VTX_SMARTAUDIO
smartAudioProcess(currentTimeUs);
#endif
#ifdef VTX_TRAMP
trampProcess(currentTimeUs);
#ifdef VTX_COMMON
vtxCommonProcess(currentTimeUs);
#endif
}
#endif
@ -555,6 +551,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
.taskFunc = rcSplitProcess,
.desiredPeriod = TASK_PERIOD_HZ(10), // 10 Hz, 100ms
.staticPriority = TASK_PRIORITY_MEDIUM,
},
#endif
#ifdef VTX_CONTROL

155
src/main/io/vtx_control.c Normal file
View file

@ -0,0 +1,155 @@
/*
* 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/>.
*/
// Get target build configuration
#include "platform.h"
#include "common/maths.h"
#include "config/config_eeprom.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "drivers/vtx_common.h"
#include "drivers/light_led.h"
#include "drivers/system.h"
#include "fc/config.h"
#include "fc/runtime_config.h"
#include "io/beeper.h"
#include "io/osd.h"
#include "io/vtx_control.h"
#if defined(VTX_CONTROL) && defined(VTX_COMMON)
PG_REGISTER(vtxConfig_t, vtxConfig, PG_VTX_CONFIG, 1);
static uint8_t locked = 0;
void vtxControlInit(void)
{
// NOTHING TO DO
}
static void vtxUpdateBandAndChannel(uint8_t bandStep, uint8_t channelStep)
{
if (ARMING_FLAG(ARMED)) {
locked = 1;
}
if (!locked) {
uint8_t band = 0, channel = 0;
vtxCommonGetBandAndChannel(&band, &channel);
vtxCommonSetBandAndChannel(band + bandStep, channel + channelStep);
}
}
void vtxIncrementBand(void)
{
vtxUpdateBandAndChannel(+1, 0);
}
void vtxDecrementBand(void)
{
vtxUpdateBandAndChannel(-1, 0);
}
void vtxIncrementChannel(void)
{
vtxUpdateBandAndChannel(0, +1);
}
void vtxDecrementChannel(void)
{
vtxUpdateBandAndChannel(0, -1);
}
void vtxUpdateActivatedChannel(void)
{
if (ARMING_FLAG(ARMED)) {
locked = 1;
}
if (!locked) {
static uint8_t lastIndex = -1;
for (uint8_t index = 0; index < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT; index++) {
const vtxChannelActivationCondition_t *vtxChannelActivationCondition = &vtxConfig()->vtxChannelActivationConditions[index];
if (isRangeActive(vtxChannelActivationCondition->auxChannelIndex, &vtxChannelActivationCondition->range)
&& index != lastIndex) {
lastIndex = index;
vtxCommonSetBandAndChannel(vtxChannelActivationCondition->band, vtxChannelActivationCondition->channel);
break;
}
}
}
}
void vtxCycleBandOrChannel(const uint8_t bandStep, const uint8_t channelStep)
{
uint8_t band = 0, channel = 0;
vtxDeviceCapability_t capability;
bool haveAllNeededInfo = vtxCommonGetBandAndChannel(&band, &channel) && vtxCommonGetDeviceCapability(&capability);
if (!haveAllNeededInfo) {
return;
}
int newChannel = channel + channelStep;
if (newChannel > capability.channelCount) {
newChannel = 1;
} else if (newChannel < 1) {
newChannel = capability.channelCount;
}
int newBand = band + bandStep;
if (newBand > capability.bandCount) {
newBand = 1;
} else if (newBand < 1) {
newBand = capability.bandCount;
}
vtxCommonSetBandAndChannel(newBand, newChannel);
}
void vtxCyclePower(const uint8_t powerStep)
{
uint8_t power = 0;
vtxDeviceCapability_t capability;
bool haveAllNeededInfo = vtxCommonGetPowerIndex(&power) && vtxCommonGetDeviceCapability(&capability);
if (!haveAllNeededInfo) {
return;
}
int newPower = power + powerStep;
if (newPower >= capability.powerCount) {
newPower = 0;
} else if (newPower < 0) {
newPower = capability.powerCount;
}
vtxCommonSetPowerByIndex(newPower);
}
#endif

49
src/main/io/vtx_control.h Normal file
View file

@ -0,0 +1,49 @@
/*
* 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/>.
*/
#pragma once
#include "fc/rc_controls.h"
#define MAX_CHANNEL_ACTIVATION_CONDITION_COUNT 10
typedef struct vtxChannelActivationCondition_s {
uint8_t auxChannelIndex;
uint8_t band;
uint8_t channel;
channelRange_t range;
} vtxChannelActivationCondition_t;
typedef struct vtxConfig_s {
vtxChannelActivationCondition_t vtxChannelActivationConditions[MAX_CHANNEL_ACTIVATION_CONDITION_COUNT];
} vtxConfig_t;
PG_DECLARE(vtxConfig_t, vtxConfig);
void vtxControlInit(void);
void vtxIncrementBand(void);
void vtxDecrementBand(void);
void vtxIncrementChannel(void);
void vtxDecrementChannel(void);
void vtxCyclePower(const uint8_t powerStep);
void vtxCycleBandOrChannel(const uint8_t bandStep, const uint8_t channelStep);
void vtxUpdateActivatedChannel(void);
void handleVTXControlButton(void);

View file

@ -19,25 +19,28 @@
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <ctype.h>
#include "platform.h"
#if defined(VTX_SMARTAUDIO) && defined(VTX_CONTROL)
#include "build/build_config.h"
#include "cms/cms.h"
#include "cms/cms_types.h"
#include "string.h"
#include "common/axis.h"
#include "common/printf.h"
#include "common/utils.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "drivers/system.h"
#include "drivers/serial.h"
#include "drivers/time.h"
#include "io/serial.h"
#include "io/vtx_smartaudio.h"
#include "io/vtx_common.h"
#include "drivers/vtx_common.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
@ -45,7 +48,9 @@
#include "flight/pid.h"
#include "config/config_master.h"
#include "build/build_config.h"
#include "io/serial.h"
#include "io/vtx_smartaudio.h"
#include "io/vtx_string.h"
//#define SMARTAUDIO_DPRINTF
//#define SMARTAUDIO_DEBUG_MONITOR
@ -72,6 +77,25 @@ static void saUpdateStatusString(void); // Forward
static serialPort_t *smartAudioSerialPort = NULL;
#if defined(CMS) || defined(VTX_COMMON)
static const char * const saPowerNames[] = {
"---", "25 ", "200", "500", "800",
};
#endif
#ifdef VTX_COMMON
static const vtxVTable_t saVTable; // Forward
static vtxDevice_t vtxSmartAudio = {
.vTable = &saVTable,
.capability.bandCount = 5,
.capability.channelCount = 8,
.capability.powerCount = 4,
.bandNames = (char **)vtx58BandNames,
.channelNames = (char **)vtx58ChannelNames,
.powerNames = (char **)saPowerNames,
};
#endif
// SmartAudio command and response codes
enum {
SA_CMD_NONE = 0x00,
@ -150,7 +174,7 @@ static saPowerTable_t saPowerTable[] = {
typedef struct smartAudioDevice_s {
int8_t version;
int8_t chan;
int8_t channel;
int8_t power;
int8_t mode;
uint16_t freq;
@ -159,7 +183,7 @@ typedef struct smartAudioDevice_s {
static smartAudioDevice_t saDevice = {
.version = 0,
.chan = -1,
.channel = -1,
.power = -1,
.mode = 0,
.freq = 0,
@ -218,7 +242,7 @@ static void saPrintSettings(void)
dprintf((" outb=%s", (saDevice.mode & 8) ? "on " : "off"));
dprintf((" lock=%s", (saDevice.mode & 16) ? "unlocked" : "locked"));
dprintf((" deferred=%s\r\n", (saDevice.mode & 32) ? "on" : "off"));
dprintf((" chan: %d ", saDevice.chan));
dprintf((" channel: %d ", saDevice.channel));
dprintf(("freq: %d ", saDevice.freq));
dprintf(("power: %d ", saDevice.power));
dprintf(("pitfreq: %d ", saDevice.orfreq));
@ -230,11 +254,11 @@ static int saDacToPowerIndex(int dac)
{
int idx;
for (idx = 0 ; idx < 4 ; idx++) {
for (idx = 3 ; idx >= 0 ; idx--) {
if (saPowerTable[idx].valueV1 <= dac)
return(idx);
}
return(3);
return(0);
}
//
@ -318,14 +342,14 @@ static void saProcessResponse(uint8_t *buf, int len)
break;
saDevice.version = (buf[0] == SA_CMD_GET_SETTINGS) ? 1 : 2;
saDevice.chan = buf[2];
saDevice.channel = buf[2];
saDevice.power = buf[3];
saDevice.mode = buf[4];
saDevice.freq = (buf[5] << 8)|buf[6];
#ifdef SMARTAUDIO_DEBUG_MONITOR
debug[0] = saDevice.version * 100 + saDevice.mode;
debug[1] = saDevice.chan;
debug[1] = saDevice.channel;
debug[2] = saDevice.freq;
debug[3] = saDevice.power;
#endif
@ -369,6 +393,10 @@ static void saProcessResponse(uint8_t *buf, int len)
saPrintSettings();
saDevicePrev = saDevice;
#ifdef VTX_COMMON
// Todo: Update states in saVtxDevice?
#endif
#ifdef CMS
// Export current device status for CMS
saCmsUpdate();
@ -603,11 +631,11 @@ static void saGetPitFreq(void)
}
#endif
void saSetBandChan(uint8_t band, uint8_t chan)
void saSetBandAndChannel(uint8_t band, uint8_t channel)
{
static uint8_t buf[6] = { 0xAA, 0x55, SACMD(SA_CMD_SET_CHAN), 1 };
buf[4] = band * 8 + chan;
buf[4] = band * 8 + channel;
buf[5] = CRC8(buf, 5);
saQueueCmd(buf, 6);
@ -642,7 +670,7 @@ void saSetPowerByIndex(uint8_t index)
saQueueCmd(buf, 6);
}
bool smartAudioInit()
bool vtxSmartAudioInit()
{
#ifdef SMARTAUDIO_DPRINTF
// Setup debugSerialPort
@ -663,10 +691,12 @@ bool smartAudioInit()
return false;
}
vtxCommonRegisterDevice(&vtxSmartAudio);
return true;
}
void smartAudioProcess(timeUs_t now)
void vtxSAProcess(uint32_t now)
{
static bool initialSent = false;
@ -705,7 +735,119 @@ void smartAudioProcess(timeUs_t now)
saGetSettings();
saSendQueue();
}
#ifdef SMARTAUDIO_TEST_VTX_COMMON
// Testing VTX_COMMON API
{
static uint32_t lastMonitorUs = 0;
if (cmp32(now, lastMonitorUs) < 5 * 1000 * 1000)
return;
static uint8_t monBand;
static uint8_t monChan;
static uint8_t monPower;
vtxCommonGetBandAndChannel(&monBand, &monChan);
vtxCommonGetPowerIndex(&monPower);
debug[0] = monBand;
debug[1] = monChan;
debug[2] = monPower;
}
#endif
}
#ifdef VTX_COMMON
// Interface to common VTX API
vtxDevType_e vtxSAGetDeviceType(void)
{
return VTXDEV_SMARTAUDIO;
}
bool vtxSAIsReady(void)
{
return !(saDevice.version == 0);
}
void vtxSASetBandAndChannel(uint8_t band, uint8_t channel)
{
if (band && channel)
saSetBandAndChannel(band - 1, channel - 1);
}
void vtxSASetPowerByIndex(uint8_t index)
{
if (index == 0) {
// SmartAudio doesn't support power off.
return;
}
saSetPowerByIndex(index - 1);
}
void vtxSASetPitMode(uint8_t onoff)
{
if (!(vtxSAIsReady() && (saDevice.version == 2)))
return;
if (onoff) {
// SmartAudio can not turn pit mode on by software.
return;
}
uint8_t newmode = SA_MODE_CLR_PITMODE;
if (saDevice.mode & SA_MODE_GET_IN_RANGE_PITMODE)
newmode |= SA_MODE_SET_IN_RANGE_PITMODE;
if (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE)
newmode |= SA_MODE_SET_OUT_RANGE_PITMODE;
saSetMode(newmode);
return;
}
bool vtxSAGetBandAndChannel(uint8_t *pBand, uint8_t *pChannel)
{
if (!vtxSAIsReady())
return false;
*pBand = (saDevice.channel / 8) + 1;
*pChannel = (saDevice.channel % 8) + 1;
return true;
}
bool vtxSAGetPowerIndex(uint8_t *pIndex)
{
if (!vtxSAIsReady())
return false;
*pIndex = ((saDevice.version == 1) ? saDacToPowerIndex(saDevice.power) : saDevice.power) + 1;
return true;
}
bool vtxSAGetPitMode(uint8_t *pOnOff)
{
if (!(vtxSAIsReady() && (saDevice.version == 2)))
return false;
*pOnOff = (saDevice.mode & SA_MODE_GET_PITMODE) ? 1 : 0;
return true;
}
static const vtxVTable_t saVTable = {
.process = vtxSAProcess,
.getDeviceType = vtxSAGetDeviceType,
.isReady = vtxSAIsReady,
.setBandAndChannel = vtxSASetBandAndChannel,
.setPowerByIndex = vtxSASetPowerByIndex,
.setPitMode = vtxSASetPitMode,
.getBandAndChannel = vtxSAGetBandAndChannel,
.getPowerIndex = vtxSAGetPowerIndex,
.getPitMode = vtxSAGetPitMode,
};
#endif // VTX_COMMON
#ifdef CMS
@ -730,7 +872,7 @@ uint8_t saCmsBand = 0;
uint8_t saCmsChan = 0;
uint8_t saCmsPower = 0;
// Frequency derived from channel table (used for reference in band/chan mode)
// Frequency derived from channel table (used for reference in band/channel mode)
uint16_t saCmsFreqRef = 0;
uint16_t saCmsDeviceFreq = 0;
@ -756,11 +898,11 @@ void saCmsUpdate(void)
saCmsFselMode = (saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ) ? 1 : 0;
saCmsBand = (saDevice.chan / 8) + 1;
saCmsChan = (saDevice.chan % 8) + 1;
saCmsFreqRef = vtx58FreqTable[saDevice.chan / 8][saDevice.chan % 8];
saCmsBand = (saDevice.channel / 8) + 1;
saCmsChan = (saDevice.channel % 8) + 1;
saCmsFreqRef = vtx58frequencyTable[saDevice.channel / 8][saDevice.channel % 8];
saCmsDeviceFreq = vtx58FreqTable[saDevice.chan / 8][saDevice.chan % 8];
saCmsDeviceFreq = vtx58frequencyTable[saDevice.channel / 8][saDevice.channel % 8];
if ((saDevice.mode & SA_MODE_GET_PITMODE) == 0) {
saCmsRFState = SACMS_TXMODE_ACTIVE;
@ -808,9 +950,15 @@ if (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE)
else
saCmsPitFMode = 0;
saCmsStatusString[0] = "-FP"[(saDevice.mode & SA_MODE_GET_PITMODE) ? SACMS_OPMODEL_RACE : SACMS_OPMODEL_FREE];
saCmsStatusString[2] = "ABEFR"[saDevice.chan / 8];
saCmsStatusString[3] = '1' + (saDevice.chan % 8);
saCmsStatusString[0] = "-FR"[saCmsOpmodel];
if (saCmsFselMode == 0) {
saCmsStatusString[2] = "ABEFR"[saDevice.channel / 8];
saCmsStatusString[3] = '1' + (saDevice.channel % 8);
} else {
saCmsStatusString[2] = 'U';
saCmsStatusString[3] = 'F';
}
if ((saDevice.mode & SA_MODE_GET_PITMODE)
&& (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE))
@ -819,7 +967,7 @@ else
tfp_sprintf(&saCmsStatusString[5], "%4d", saDevice.freq);
else
tfp_sprintf(&saCmsStatusString[5], "%4d",
vtx58FreqTable[saDevice.chan / 8][saDevice.chan % 8]);
vtx58frequencyTable[saDevice.channel / 8][saDevice.channel % 8]);
saCmsStatusString[9] = ' ';
@ -848,18 +996,16 @@ static long saCmsConfigBandByGvar(displayPort_t *pDisp, const void *self)
return 0;
}
dprintf(("saCmsConfigBand: band req %d ", saCmsBand));
if (saCmsBand == 0) {
// Bouce back, no going back to undef state
saCmsBand = 1;
return 0;
}
if (!(saCmsOpmodel == SACMS_OPMODEL_FREE && saDeferred))
saSetBandChan(saCmsBand - 1, saCmsChan - 1);
if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred)
saSetBandAndChannel(saCmsBand - 1, saCmsChan - 1);
saCmsFreqRef = vtx58FreqTable[saCmsBand - 1][saCmsChan - 1];
saCmsFreqRef = vtx58frequencyTable[saCmsBand - 1][saCmsChan - 1];
return 0;
}
@ -881,10 +1027,10 @@ static long saCmsConfigChanByGvar(displayPort_t *pDisp, const void *self)
return 0;
}
if (!(saCmsOpmodel == SACMS_OPMODEL_FREE && saDeferred))
saSetBandChan(saCmsBand - 1, saCmsChan - 1);
if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred)
saSetBandAndChannel(saCmsBand - 1, saCmsChan - 1);
saCmsFreqRef = vtx58FreqTable[saCmsBand - 1][saCmsChan - 1];
saCmsFreqRef = vtx58frequencyTable[saCmsBand - 1][saCmsChan - 1];
return 0;
}
@ -906,6 +1052,7 @@ static long saCmsConfigPowerByGvar(displayPort_t *pDisp, const void *self)
return 0;
}
if (saCmsOpmodel == SACMS_OPMODEL_FREE)
saSetPowerByIndex(saCmsPower - 1);
return 0;
@ -927,6 +1074,8 @@ static long saCmsConfigPitFModeByGvar(displayPort_t *pDisp, const void *self)
return 0;
}
static long saCmsConfigFreqModeByGvar(displayPort_t *pDisp, const void *self); // Forward
static long saCmsConfigOpmodelByGvar(displayPort_t *pDisp, const void *self)
{
UNUSED(pDisp);
@ -946,6 +1095,10 @@ static long saCmsConfigOpmodelByGvar(displayPort_t *pDisp, const void *self)
// out-range receivers from getting blinded.
saCmsPitFMode = 0;
saCmsConfigPitFModeByGvar(pDisp, self);
// Direct frequency mode is not available in RACE opmodel
saCmsFselMode = 0;
saCmsConfigFreqModeByGvar(pDisp, self);
} else {
// Trying to go back to unknown state; bounce back
saCmsOpmodel = SACMS_OPMODEL_UNDEF + 1;
@ -1028,7 +1181,7 @@ static long saCmsConfigFreqModeByGvar(displayPort_t *pDisp, const void *self)
if (saCmsFselMode == 0) {
// CHAN
saSetBandChan(saCmsBand - 1, saCmsChan - 1);
saSetBandAndChannel(saCmsBand - 1, saCmsChan - 1);
} else {
// USER: User frequency mode is only available in FREE opmodel.
if (saCmsOpmodel == SACMS_OPMODEL_FREE) {
@ -1050,17 +1203,28 @@ static long saCmsCommence(displayPort_t *pDisp, const void *self)
UNUSED(self);
if (saCmsOpmodel == SACMS_OPMODEL_RACE) {
// Race model
// Setup band, freq and power.
saSetBandAndChannel(saCmsBand - 1, saCmsChan - 1);
// If in pit mode, cancel it.
if (saCmsPitFMode == 0)
saSetMode(SA_MODE_CLR_PITMODE|SA_MODE_SET_IN_RANGE_PITMODE);
else
saSetMode(SA_MODE_CLR_PITMODE|SA_MODE_SET_OUT_RANGE_PITMODE);
} else {
// Freestyle model
// Setup band and freq / user freq
if (saCmsFselMode == 0)
saSetBandChan(saCmsBand - 1, saCmsChan - 1);
saSetBandAndChannel(saCmsBand - 1, saCmsChan - 1);
else
saSetFreq(saCmsUserFreq);
}
saSetPowerByIndex(saCmsPower - 1);
return MENU_CHAIN_BACK;
}
@ -1106,15 +1270,15 @@ static long saCmsSetUserFreqOnEnter(void)
return 0;
}
static long saCmsSetUserFreq(displayPort_t *pDisp, const void *self)
static long saCmsConfigUserFreq(displayPort_t *pDisp, const void *self)
{
UNUSED(pDisp);
UNUSED(self);
saCmsUserFreq = saCmsUserFreqNew;
saSetFreq(saCmsUserFreq);
//saSetFreq(saCmsUserFreq);
return 0;
return MENU_CHAIN_BACK;
}
static OSD_Entry saCmsMenuPORFreqEntries[] = {
@ -1143,7 +1307,7 @@ static OSD_Entry saCmsMenuUserFreqEntries[] = {
{ "CUR FREQ", OME_UINT16, NULL, &(OSD_UINT16_t){ &saCmsUserFreq, 5000, 5900, 0 }, DYNAMIC },
{ "NEW FREQ", OME_UINT16, NULL, &(OSD_UINT16_t){ &saCmsUserFreqNew, 5000, 5900, 1 }, 0 },
{ "SET", OME_Funcall, saCmsSetUserFreq, NULL, 0 },
{ "SET", OME_Funcall, saCmsConfigUserFreq, NULL, 0 },
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
@ -1164,8 +1328,8 @@ static OSD_TAB_t saCmsEntFselMode = { &saCmsFselMode, 1, saCmsFselModeNames };
static OSD_Entry saCmsMenuConfigEntries[] = {
{ "- SA CONFIG -", OME_Label, NULL, NULL, 0 },
{ "OP MODEL", OME_TAB, saCmsConfigOpmodelByGvar, &(OSD_TAB_t){ &saCmsOpmodel, 2, saCmsOpmodelNames }, 0 },
{ "FSEL MODE", OME_TAB, saCmsConfigFreqModeByGvar, &saCmsEntFselMode, 0 },
{ "OP MODEL", OME_TAB, saCmsConfigOpmodelByGvar, &(OSD_TAB_t){ &saCmsOpmodel, 2, saCmsOpmodelNames }, DYNAMIC },
{ "FSEL MODE", OME_TAB, saCmsConfigFreqModeByGvar, &saCmsEntFselMode, DYNAMIC },
{ "PIT FMODE", OME_TAB, saCmsConfigPitFModeByGvar, &saCmsEntPitFMode, 0 },
{ "POR FREQ", OME_Submenu, (CMSEntryFuncPtr)saCmsORFreqGetString, &saCmsMenuPORFreq, OPTSTRING },
{ "STATX", OME_Submenu, cmsMenuChange, &saCmsMenuStats, 0 },

View file

@ -1,8 +1,7 @@
// For generic API use, but here for now
bool smartAudioInit();
void smartAudioProcess(timeUs_t);
bool vtxSmartAudioInit();
#if 0
#ifdef CMS

View file

@ -25,9 +25,9 @@
#include "platform.h"
#include "build/debug.h"
#if defined(VTX_CONTROL)
#if defined(VTX_COMMON)
const uint16_t vtx58FreqTable[5][8] =
const uint16_t vtx58frequencyTable[5][8] =
{
{ 5865, 5845, 5825, 5805, 5785, 5765, 5745, 5725 }, // Boscam A
{ 5733, 5752, 5771, 5790, 5809, 5828, 5847, 5866 }, // Boscam B
@ -51,23 +51,25 @@ const char * const vtx58ChannelNames[] = {
"-", "1", "2", "3", "4", "5", "6", "7", "8",
};
bool vtx58_Freq2Bandchan(uint16_t freq, uint8_t *pBand, uint8_t *pChan)
bool vtx58_Freq2Bandchan(uint16_t freq, uint8_t *pBand, uint8_t *pChannel)
{
uint8_t band;
uint8_t chan;
int8_t band;
uint8_t channel;
for (band = 0 ; band < 5 ; band++) {
for (chan = 0 ; chan < 8 ; chan++) {
if (vtx58FreqTable[band][chan] == freq) {
// Use reverse lookup order so that 5880Mhz
// get Raceband 7 instead of Fatshark 8.
for (band = 4 ; band >= 0 ; band--) {
for (channel = 0 ; channel < 8 ; channel++) {
if (vtx58frequencyTable[band][channel] == freq) {
*pBand = band + 1;
*pChan = chan + 1;
*pChannel = channel + 1;
return true;
}
}
}
*pBand = 0;
*pChan = 0;
*pChannel = 0;
return false;
}

View file

@ -2,13 +2,13 @@
#include <stdint.h>
#if defined(VTX_CONTROL)
#if defined(VTX_COMMON)
extern const uint16_t vtx58FreqTable[5][8];
extern const uint16_t vtx58frequencyTable[5][8];
extern const char * const vtx58BandNames[];
extern const char * const vtx58ChannelNames[];
extern const char vtx58BandLetter[];
bool vtx58_Freq2Bandchan(uint16_t freq, uint8_t *pBand, uint8_t *pChan);
bool vtx58_Freq2Bandchan(uint16_t freq, uint8_t *pBand, uint8_t *pChannel);
#endif

View file

@ -34,8 +34,34 @@
#include "io/serial.h"
#include "drivers/serial.h"
#include "drivers/system.h"
#include "drivers/vtx_common.h"
#include "io/vtx_tramp.h"
#include "io/vtx_common.h"
#include "io/vtx_string.h"
#define TRAMP_SERIAL_OPTIONS (SERIAL_BIDIR)
#if defined(CMS) || defined(VTX_COMMON)
static const uint16_t trampPowerTable[] = {
25, 100, 200, 400, 600
};
static const char * const trampPowerNames[] = {
"---", "25 ", "100", "200", "400", "600"
};
#endif
#if defined(VTX_COMMON)
static const vtxVTable_t trampVTable; // forward
static vtxDevice_t vtxTramp = {
.vTable = &trampVTable,
.capability.bandCount = 5,
.capability.channelCount = 8,
.capability.powerCount = sizeof(trampPowerTable),
.bandNames = (char **)vtx58BandNames,
.channelNames = (char **)vtx58ChannelNames,
.powerNames = (char **)trampPowerNames,
};
#endif
static serialPort_t *trampSerialPort = NULL;
@ -57,15 +83,21 @@ uint32_t trampRFFreqMax;
uint32_t trampRFPowerMax;
uint32_t trampCurFreq = 0;
uint8_t trampCurBand = 0;
uint8_t trampCurChan = 0;
uint16_t trampCurPower = 0; // Actual transmitting power
uint16_t trampCurConfigPower = 0; // Configured transmitting power
int16_t trampCurTemp = 0;
uint8_t trampCurPitmode = 0;
uint8_t trampBand = 0;
uint8_t trampChannel = 0;
uint16_t trampPower = 0; // Actual transmitting power
uint16_t trampConfiguredPower = 0; // Configured transmitting power
int16_t trampTemperature = 0;
uint8_t trampPitMode = 0;
// Maximum number of requests sent to try a config change
#define TRAMP_MAX_RETRIES 2
uint32_t trampConfFreq = 0;
uint8_t trampFreqRetries = 0;
uint16_t trampConfPower = 0;
uint8_t trampPowerRetries = 0;
#ifdef CMS
static void trampCmsUpdateStatusString(void); // Forward
@ -103,6 +135,8 @@ void trampCmdU16(uint8_t cmd, uint16_t param)
void trampSetFreq(uint16_t freq)
{
trampConfFreq = freq;
if(trampConfFreq != trampCurFreq)
trampFreqRetries = TRAMP_MAX_RETRIES;
}
void trampSendFreq(uint16_t freq)
@ -110,14 +144,16 @@ void trampSendFreq(uint16_t freq)
trampCmdU16('F', freq);
}
void trampSetBandChan(uint8_t band, uint8_t chan)
void trampSetBandAndChannel(uint8_t band, uint8_t channel)
{
trampSetFreq(vtx58FreqTable[band - 1][chan - 1]);
trampSetFreq(vtx58frequencyTable[band - 1][channel - 1]);
}
void trampSetRFPower(uint16_t level)
{
trampConfPower = level;
if(trampConfPower != trampPower)
trampPowerRetries = TRAMP_MAX_RETRIES;
}
void trampSendRFPower(uint16_t level)
@ -135,7 +171,7 @@ bool trampCommitChanges()
return true;
}
void trampSetPitmode(uint8_t onoff)
void trampSetPitMode(uint8_t onoff)
{
trampCmdU16('I', onoff ? 0 : 1);
}
@ -165,10 +201,13 @@ char trampHandleResponse(void)
uint16_t freq = trampRespBuffer[2]|(trampRespBuffer[3] << 8);
if(freq != 0) {
trampCurFreq = freq;
trampCurConfigPower = trampRespBuffer[4]|(trampRespBuffer[5] << 8);
trampCurPitmode = trampRespBuffer[7];
trampCurPower = trampRespBuffer[8]|(trampRespBuffer[9] << 8);
vtx58_Freq2Bandchan(trampCurFreq, &trampCurBand, &trampCurChan);
trampConfiguredPower = trampRespBuffer[4]|(trampRespBuffer[5] << 8);
trampPitMode = trampRespBuffer[7];
trampPower = trampRespBuffer[8]|(trampRespBuffer[9] << 8);
vtx58_Freq2Bandchan(trampCurFreq, &trampBand, &trampChannel);
if(trampConfFreq == 0) trampConfFreq = trampCurFreq;
if(trampConfPower == 0) trampConfPower = trampPower;
return 'v';
}
@ -180,7 +219,7 @@ char trampHandleResponse(void)
{
uint16_t temp = (int16_t)(trampRespBuffer[6]|(trampRespBuffer[7] << 8));
if(temp != 0) {
trampCurTemp = temp;
trampTemperature = temp;
return 's';
}
}
@ -283,24 +322,7 @@ void trampQueryS(void)
trampQuery('s');
}
#define TRAMP_SERIAL_OPTIONS (SERIAL_BIDIR)
bool trampInit()
{
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_VTX_TRAMP);
if (portConfig) {
trampSerialPort = openSerialPort(portConfig->identifier, FUNCTION_VTX_TRAMP, NULL, 9600, MODE_RXTX, TRAMP_SERIAL_OPTIONS);
}
if (!trampSerialPort) {
return false;
}
return true;
}
void trampProcess(timeUs_t currentTimeUs)
void vtxTrampProcess(uint32_t currentTimeUs)
{
static uint32_t lastQueryTimeUs = 0;
@ -353,15 +375,17 @@ void trampProcess(timeUs_t currentTimeUs)
case TRAMP_STATUS_SET_FREQ_PW:
{
bool done = true;
if (trampConfFreq != trampCurFreq) {
if (trampConfFreq && trampFreqRetries && (trampConfFreq != trampCurFreq)) {
trampSendFreq(trampConfFreq);
trampFreqRetries--;
#ifdef TRAMP_DEBUG
debugFreqReqCounter++;
#endif
done = false;
}
else if (trampConfPower != trampCurConfigPower) {
else if (trampConfPower && trampPowerRetries && (trampConfPower != trampConfiguredPower)) {
trampSendRFPower(trampConfPower);
trampPowerRetries--;
#ifdef TRAMP_DEBUG
debugPowReqCounter++;
#endif
@ -377,6 +401,10 @@ void trampProcess(timeUs_t currentTimeUs)
else {
// everything has been done, let's return to original state
trampStatus = TRAMP_STATUS_ONLINE;
// reset configuration value in case it failed (no more retries)
trampConfFreq = trampCurFreq;
trampConfPower = trampPower;
trampFreqRetries = trampPowerRetries = 0;
}
}
break;
@ -416,8 +444,8 @@ static void trampCmsUpdateStatusString(void)
{
trampCmsStatusString[0] = '*';
trampCmsStatusString[1] = ' ';
trampCmsStatusString[2] = vtx58BandLetter[trampCurBand];
trampCmsStatusString[3] = vtx58ChannelNames[trampCurChan][0];
trampCmsStatusString[2] = vtx58BandLetter[trampBand];
trampCmsStatusString[3] = vtx58ChannelNames[trampChannel][0];
trampCmsStatusString[4] = ' ';
if (trampCurFreq)
@ -425,14 +453,14 @@ static void trampCmsUpdateStatusString(void)
else
tfp_sprintf(&trampCmsStatusString[5], "----");
if (trampCurPower) {
tfp_sprintf(&trampCmsStatusString[9], " %c%3d", (trampCurPower == trampCurConfigPower) ? ' ' : '*', trampCurPower);
if (trampPower) {
tfp_sprintf(&trampCmsStatusString[9], " %c%3d", (trampPower == trampConfiguredPower) ? ' ' : '*', trampPower);
}
else
tfp_sprintf(&trampCmsStatusString[9], " ----");
}
uint8_t trampCmsPitmode = 0;
uint8_t trampCmsPitMode = 0;
uint8_t trampCmsBand = 1;
uint8_t trampCmsChan = 1;
uint16_t trampCmsFreqRef;
@ -443,22 +471,14 @@ static OSD_TAB_t trampCmsEntChan = { &trampCmsChan, 8, vtx58ChannelNames };
static OSD_UINT16_t trampCmsEntFreqRef = { &trampCmsFreqRef, 5600, 5900, 0 };
static const char * const trampCmsPowerNames[] = {
"25 ", "100", "200", "400", "600"
};
static uint8_t trampCmsPower = 1;
static const uint16_t trampCmsPowerTable[] = {
25, 100, 200, 400, 600
};
static uint8_t trampCmsPower = 0;
static OSD_TAB_t trampCmsEntPower = { &trampCmsPower, 4, trampCmsPowerNames };
static OSD_TAB_t trampCmsEntPower = { &trampCmsPower, 5, trampPowerNames };
static void trampCmsUpdateFreqRef(void)
{
if (trampCmsBand > 0 && trampCmsChan > 0)
trampCmsFreqRef = vtx58FreqTable[trampCmsBand - 1][trampCmsChan - 1];
trampCmsFreqRef = vtx58frequencyTable[trampCmsBand - 1][trampCmsChan - 1];
}
static long trampCmsConfigBand(displayPort_t *pDisp, const void *self)
@ -489,24 +509,36 @@ static long trampCmsConfigChan(displayPort_t *pDisp, const void *self)
return 0;
}
static OSD_INT16_t trampCmsEntTemp = { &trampCurTemp, -100, 300, 0 };
static const char * const trampCmsPitmodeNames[] = {
"---", "OFF", "ON "
};
static OSD_TAB_t trampCmsEntPitmode = { &trampCmsPitmode, 2, trampCmsPitmodeNames };
static long trampCmsSetPitmode(displayPort_t *pDisp, const void *self)
static long trampCmsConfigPower(displayPort_t *pDisp, const void *self)
{
UNUSED(pDisp);
UNUSED(self);
if (trampCmsPitmode == 0) {
if (trampCmsPower == 0)
// Bounce back
trampCmsPower = 1;
return 0;
}
static OSD_INT16_t trampCmsEntTemp = { &trampTemperature, -100, 300, 0 };
static const char * const trampCmsPitModeNames[] = {
"---", "OFF", "ON "
};
static OSD_TAB_t trampCmsEntPitMode = { &trampCmsPitMode, 2, trampCmsPitModeNames };
static long trampCmsSetPitMode(displayPort_t *pDisp, const void *self)
{
UNUSED(pDisp);
UNUSED(self);
if (trampCmsPitMode == 0) {
// Bouce back
trampCmsPitmode = 1;
trampCmsPitMode = 1;
} else {
trampSetPitmode(trampCmsPitmode - 1);
trampSetPitMode(trampCmsPitMode - 1);
}
return 0;
@ -517,8 +549,8 @@ static long trampCmsCommence(displayPort_t *pDisp, const void *self)
UNUSED(pDisp);
UNUSED(self);
trampSetBandChan(trampCmsBand, trampCmsChan);
trampSetRFPower(trampCmsPowerTable[trampCmsPower]);
trampSetBandAndChannel(trampCmsBand, trampCmsChan);
trampSetRFPower(trampPowerTable[trampCmsPower-1]);
// If it fails, the user should retry later
trampCommitChanges();
@ -529,16 +561,16 @@ static long trampCmsCommence(displayPort_t *pDisp, const void *self)
static void trampCmsInitSettings()
{
if(trampCurBand > 0) trampCmsBand = trampCurBand;
if(trampCurChan > 0) trampCmsChan = trampCurChan;
if(trampBand > 0) trampCmsBand = trampBand;
if(trampChannel > 0) trampCmsChan = trampChannel;
trampCmsUpdateFreqRef();
trampCmsPitmode = trampCurPitmode + 1;
trampCmsPitMode = trampPitMode + 1;
if (trampCurConfigPower > 0) {
for (uint8_t i = 0; i < sizeof(trampCmsPowerTable); i++) {
if (trampCurConfigPower <= trampCmsPowerTable[i]) {
trampCmsPower = i;
if (trampConfiguredPower > 0) {
for (uint8_t i = 0; i < sizeof(trampPowerTable); i++) {
if (trampConfiguredPower <= trampPowerTable[i]) {
trampCmsPower = i + 1;
break;
}
}
@ -572,11 +604,11 @@ static OSD_Entry trampMenuEntries[] =
{ "- TRAMP -", OME_Label, NULL, NULL, 0 },
{ "", OME_Label, NULL, trampCmsStatusString, DYNAMIC },
{ "PIT", OME_TAB, trampCmsSetPitmode, &trampCmsEntPitmode, 0 },
{ "PIT", OME_TAB, trampCmsSetPitMode, &trampCmsEntPitMode, 0 },
{ "BAND", OME_TAB, trampCmsConfigBand, &trampCmsEntBand, 0 },
{ "CHAN", OME_TAB, trampCmsConfigChan, &trampCmsEntChan, 0 },
{ "(FREQ)", OME_UINT16, NULL, &trampCmsEntFreqRef, DYNAMIC },
{ "POWER", OME_TAB, NULL, &trampCmsEntPower, 0 },
{ "POWER", OME_TAB, trampCmsConfigPower, &trampCmsEntPower, 0 },
{ "T(C)", OME_INT16, NULL, &trampCmsEntTemp, DYNAMIC },
{ "SET", OME_Submenu, cmsMenuChange, &trampCmsMenuCommence, 0 },
@ -594,4 +626,108 @@ CMS_Menu cmsx_menuVtxTramp = {
};
#endif
#ifdef VTX_COMMON
// Interface to common VTX API
vtxDevType_e vtxTrampGetDeviceType(void)
{
return VTXDEV_TRAMP;
}
bool vtxTrampIsReady(void)
{
return trampStatus > TRAMP_STATUS_OFFLINE;
}
void vtxTrampSetBandAndChannel(uint8_t band, uint8_t channel)
{
if (band && channel) {
trampSetBandAndChannel(band, channel);
trampCommitChanges();
}
}
void vtxTrampSetPowerByIndex(uint8_t index)
{
if (index) {
trampSetRFPower(trampPowerTable[index - 1]);
trampCommitChanges();
}
}
void vtxTrampSetPitMode(uint8_t onoff)
{
trampSetPitMode(onoff);
}
bool vtxTrampGetBandAndChannel(uint8_t *pBand, uint8_t *pChannel)
{
if (!vtxTrampIsReady())
return false;
*pBand = trampBand;
*pChannel = trampChannel;
return true;
}
bool vtxTrampGetPowerIndex(uint8_t *pIndex)
{
if (!vtxTrampIsReady())
return false;
if (trampConfiguredPower > 0) {
for (uint8_t i = 0; i < sizeof(trampPowerTable); i++) {
if (trampConfiguredPower <= trampPowerTable[i]) {
*pIndex = i + 1;
break;
}
}
}
return true;
}
bool vtxTrampGetPitMode(uint8_t *pOnOff)
{
if (!vtxTrampIsReady())
return false;
*pOnOff = trampPitMode;
return true;
}
static const vtxVTable_t trampVTable = {
.process = vtxTrampProcess,
.getDeviceType = vtxTrampGetDeviceType,
.isReady = vtxTrampIsReady,
.setBandAndChannel = vtxTrampSetBandAndChannel,
.setPowerByIndex = vtxTrampSetPowerByIndex,
.setPitMode = vtxTrampSetPitMode,
.getBandAndChannel = vtxTrampGetBandAndChannel,
.getPowerIndex = vtxTrampGetPowerIndex,
.getPitMode = vtxTrampGetPitMode,
};
#endif
bool vtxTrampInit(void)
{
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_VTX_TRAMP);
if (portConfig) {
trampSerialPort = openSerialPort(portConfig->identifier, FUNCTION_VTX_TRAMP, NULL, 9600, MODE_RXTX, TRAMP_SERIAL_OPTIONS);
}
if (!trampSerialPort) {
return false;
}
#if defined(VTX_COMMON)
vtxCommonRegisterDevice(&vtxTramp);
#endif
return true;
}
#endif // VTX_TRAMP

View file

@ -2,8 +2,7 @@
#if defined(VTX_TRAMP) && defined(VTX_CONTROL)
bool trampInit();
void trampProcess(timeUs_t currentTimeUs);
bool vtxTrampInit();
#ifdef CMS
#include "cms/cms.h"

View file

@ -97,6 +97,7 @@
#define USE_RCSPLIT
#define PITOT
#define USE_PITOT_ADC
#define VTX_COMMON
#define VTX_CONTROL
#define VTX_SMARTAUDIO
#define VTX_TRAMP