VTX abstraction (experimental)

This commit is contained in:
jflyper 2017-01-15 01:27:02 +09:00
parent 2d6b718896
commit cdd0cd4528
9 changed files with 573 additions and 24 deletions

View File

@ -591,6 +591,8 @@ HIGHEND_SRC = \
drivers/serial_escserial.c \ drivers/serial_escserial.c \
drivers/serial_softserial.c \ drivers/serial_softserial.c \
drivers/sonar_hcsr04.c \ drivers/sonar_hcsr04.c \
drivers/vtx_var.c \
drivers/vtx_common.c \
flight/navigation.c \ flight/navigation.c \
flight/gps_conversion.c \ flight/gps_conversion.c \
io/dashboard.c \ io/dashboard.c \
@ -704,6 +706,8 @@ SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \
SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \ SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
drivers/serial_escserial.c \ drivers/serial_escserial.c \
drivers/vtx_var.c \
drivers/vtx_common.c \
io/cli.c \ io/cli.c \
io/serial_4way.c \ io/serial_4way.c \
io/serial_4way_avrootloader.c \ io/serial_4way_avrootloader.c \

View File

@ -0,0 +1,140 @@
/*
* 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"
#include "vtx_var.h"
vtxDevice_t *vtxDevice = NULL;
void vtxCommonInit(void)
{
}
// Whatever registered last will win
void vtxCommonRegisterDevice(vtxDevice_t *pDevice)
{
vtxDevice = pDevice;
}
vtxDevType_e vtxCommonGetDeviceType(void)
{
if (!vtxDevice)
return VTXDEV_UNKNOWN;
return vtxDevice->devtype;
}
// band and chan are 1 origin
void vtxCommonSetBandChan(uint8_t band, uint8_t chan)
{
if (!vtxDevice)
return;
if (vtxDevice->vTable->setBandChan)
vtxDevice->vTable->setBandChan(band, chan);
}
// index is zero origin, zero = power off completely
void vtxCommonSetPowerByIndex(uint8_t index)
{
if (!vtxDevice)
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 vtxCommonGetBandChan(uint8_t *pBand, uint8_t *pChan)
{
if (!vtxDevice)
return false;
if (vtxDevice->vTable->getBandChan)
return vtxDevice->vTable->getBandChan(pBand, pChan);
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;
}
// Utilities
bool vtx58_Freq2Bandchan(uint16_t freq, uint8_t *pBand, uint8_t *pChan)
{
uint8_t band;
uint8_t chan;
for (band = 0 ; band < 5 ; band++) {
for (chan = 0 ; chan < 8 ; chan++) {
if (vtx58FreqTable[band][chan] == freq) {
*pBand = band + 1;
*pChan = chan + 1;
return true;
}
}
}
*pBand = 0;
*pChan = 0;
return false;
}
#endif

View File

@ -0,0 +1,82 @@
/*
* 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 */
typedef enum {
VTXDEV_UNKNOWN = 0,
VTXDEV_SMARTAUDIO = 3,
VTXDEV_TRAMP = 4,
} vtxDevType_e;
struct vtxVTable_s;
typedef struct vtxDevice_s {
const struct vtxVTable_s *vTable;
vtxDevType_e devtype; // 3.1 only; eventually goes away
uint8_t numBand;
uint8_t numChan;
uint8_t numPower;
uint16_t *freqTable; // Array of [numBand][numChan]
char **bandNames; // char *bandNames[numBand]
char **chanNames; // char *chanNames[numChan]
char **powerNames; // char *powerNames[numPower]
uint8_t curBand;
uint8_t curChan;
uint8_t curPowerIndex;
uint8_t curPitState; // 0 = non-PIT, 1 = PIT
} vtxDevice_t;
// {set,get}BandChan: band and chan are 1 origin
// {set,get}PowerByIndex: 0 = Power OFF, 1 = device dependent
// {set,get}Pitmode: 0 = OFF, 1 = ON
typedef struct vtxVTable_s {
vtxDevType_e (*getDeviceType)(void);
bool (*isReady)(void);
void (*setBandChan)(uint8_t band, uint8_t chan);
void (*setPowerByIndex)(uint8_t level);
void (*setPitmode)(uint8_t onoff);
bool (*getBandChan)(uint8_t *pBand, uint8_t *pChan);
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);
uint8_t vtxCommonGetDeviceType(void);
void vtxCommonSetBandChan(uint8_t band, uint8_t chan);
void vtxCommonSetPowerByIndex(uint8_t level);
void vtxCommonSetPitmode(uint8_t onoff);
bool vtxCommonGetBandChan(uint8_t *pBand, uint8_t *pChan);
bool vtxCommonGetPowerIndex(uint8_t *pIndex);
bool vtxCommonGetPitmode(uint8_t *pOnoff);
bool vtx58_Freq2Bandchan(uint16_t freq, uint8_t *pBand, uint8_t *pChan);

View File

@ -0,0 +1,45 @@
/*
* 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 <stdint.h>
#include "vtx_var.h"
const uint16_t vtx58FreqTable[5][8] =
{
{ 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 * const vtx58BandNames[] = {
"--------",
"BOSCAM A",
"BOSCAM B",
"BOSCAM E",
"FATSHARK",
"RACEBAND",
};
const char vtx58BandLetter[] = "-ABEFR";
const char * const vtx58ChanNames[] = {
"-", "1", "2", "3", "4", "5", "6", "7", "8",
};

View File

@ -0,0 +1,27 @@
/*
* 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 */
#pragma once
#include <stdint.h>
extern const uint16_t vtx58FreqTable[5][8];
extern const char * const vtx58BandNames[];
extern const char * const vtx58ChanNames[];
extern const char vtx58BandLetter[];

View File

@ -0,0 +1,110 @@
/*
* 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"
#ifdef VTX_SINGULARITY
// Own interfaces
#include "io/vtx_singularity.h"
#include "io/osd.h"
//External dependencies
#include "config/config_master.h"
#include "config/config_eeprom.h"
#include "drivers/vtx_rtc6705.h"
#include "fc/runtime_config.h"
#include "io/beeper.h"
static uint8_t locked = 0;
void vtxSingularityInit(void)
{
rtc6705Init();
if (masterConfig.vtx_mode == 0) {
rtc6705SetChannel(masterConfig.vtx_band, masterConfig.vtx_channel);
} else if (masterConfig.vtx_mode == 1) {
rtc6705SetFreq(masterConfig.vtx_mhz);
}
}
static void setChannelSaveAndNotify(uint8_t *bandOrChannel, uint8_t step, int32_t min, int32_t max)
{
if (ARMING_FLAG(ARMED)) {
locked = 1;
}
if (masterConfig.vtx_mode == 0 && !locked) {
uint8_t temp = (*bandOrChannel) + step;
temp = constrain(temp, min, max);
*bandOrChannel = temp;
rtc6705SetChannel(masterConfig.vtx_band, masterConfig.vtx_channel);
writeEEPROM();
readEEPROM();
beeperConfirmationBeeps(temp);
}
}
void vtxSingularityIncrementBand(void)
{
setChannelSaveAndNotify(&(masterConfig.vtx_band), 1, RTC6705_BAND_MIN, RTC6705_BAND_MAX);
}
void vtxSingularityDecrementBand(void)
{
setChannelSaveAndNotify(&(masterConfig.vtx_band), -1, RTC6705_BAND_MIN, RTC6705_BAND_MAX);
}
void vtxSingularityIncrementChannel(void)
{
setChannelSaveAndNotify(&(masterConfig.vtx_channel), 1, RTC6705_CHANNEL_MIN, RTC6705_CHANNEL_MAX);
}
void vtxSingularityDecrementChannel(void)
{
setChannelSaveAndNotify(&(masterConfig.vtx_channel), -1, RTC6705_CHANNEL_MIN, RTC6705_CHANNEL_MAX);
}
void vtxSingularityUpdateActivatedChannel(void)
{
if (ARMING_FLAG(ARMED)) {
locked = 1;
}
if (masterConfig.vtx_mode == 2 && !locked) {
static uint8_t lastIndex = -1;
uint8_t index;
for (index = 0; index < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT; index++) {
vtxChannelActivationCondition_t *vtxChannelActivationCondition = &masterConfig.vtxChannelActivationConditions[index];
if (isRangeActive(vtxChannelActivationCondition->auxChannelIndex, &vtxChannelActivationCondition->range)
&& index != lastIndex) {
lastIndex = index;
rtc6705SetChannel(vtxChannelActivationCondition->band, vtxChannelActivationCondition->channel);
break;
}
}
}
}
#endif

View File

@ -0,0 +1,41 @@
/*
* 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 VTX_BAND_MIN 1
#define VTX_BAND_MAX 5
#define VTX_CHANNEL_MIN 1
#define VTX_CHANNEL_MAX 8
#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;
void vtxSingularityInit(void);
void vtxSingularityIncrementBand(void);
void vtxSingularityDecrementBand(void);
void vtxSingularityIncrementChannel(void);
void vtxSingularityDecrementChannel(void);
void vtxSingularityUpdateActivatedChannel(void);

View File

@ -33,6 +33,8 @@
#include "common/utils.h" #include "common/utils.h"
#include "drivers/system.h" #include "drivers/system.h"
#include "drivers/serial.h" #include "drivers/serial.h"
#include "drivers/vtx_var.h"
#include "drivers/vtx_common.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/vtx_smartaudio.h" #include "io/vtx_smartaudio.h"
@ -69,6 +71,25 @@ static void saUpdateStatusString(void); // Forward
static serialPort_t *smartAudioSerialPort = NULL; 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 vtxVTable_t saVTable; // Forward
static vtxDevice_t vtxSmartAudio = {
.vTable = &saVTable,
.numBand = 5,
.numChan = 8,
.numPower = 4,
.bandNames = (char **)vtx58BandNames,
.chanNames = (char **)vtx58ChanNames,
.powerNames = (char **)saPowerNames,
};
#endif
// SmartAudio command and response codes // SmartAudio command and response codes
enum { enum {
SA_CMD_NONE = 0x00, SA_CMD_NONE = 0x00,
@ -378,6 +399,10 @@ static void saProcessResponse(uint8_t *buf, int len)
saPrintSettings(); saPrintSettings();
saDevicePrev = saDevice; saDevicePrev = saDevice;
#ifdef VTX_COMMON
// Todo: Update states in saVtxDevice?
#endif
#ifdef CMS #ifdef CMS
// Export current device status for CMS // Export current device status for CMS
saCmsUpdate(); saCmsUpdate();
@ -672,6 +697,9 @@ bool smartAudioInit()
return false; return false;
} }
vtxSmartAudio.vTable = &saVTable;
vtxCommonRegisterDevice(&vtxSmartAudio);
return true; return true;
} }
@ -716,6 +744,98 @@ void smartAudioProcess(uint32_t now)
} }
} }
#ifdef VTX_COMMON
// Interface to common VTX API
vtxDevType_e vtxSAGetDeviceType(void)
{
return VTXDEV_SMARTAUDIO;
}
bool vtxSAIsReady(void)
{
return !(saDevice.version == 0);
}
void vtxSASetBandChan(uint8_t band, uint8_t chan)
{
if (band && chan)
saSetBandChan(band - 1, chan - 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 true;
}
bool vtxSAGetBandChan(uint8_t *pBand, uint8_t *pChan)
{
if (!vtxSAIsReady())
return false;
*pBand = (saDevice.chan / 8) + 1;
*pChan = (saDevice.chan % 8) + 1;
return true;
}
bool vtxSAGetPowerIndex(uint8_t *pIndex)
{
if (!vtxSAIsReady())
return false;
*pIndex = (saDevice.version == 1) ? saDacToPowerIndex(saDevice.power) : saDevice.power;
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 vtxVTable_t saVTable = {
.getDeviceType = vtxSAGetDeviceType,
.isReady = vtxSAIsReady,
.setBandChan = vtxSASetBandChan,
.setPowerByIndex = vtxSASetPowerByIndex,
.setPitmode = vtxSASetPitmode,
.getBandChan = vtxSAGetBandChan,
.getPowerIndex = vtxSAGetPowerIndex,
.getPitmode = vtxSAGetPitmode,
};
#endif // VTX_COMMON
#ifdef CMS #ifdef CMS
// Interface to CMS // Interface to CMS
@ -994,32 +1114,11 @@ static CMS_Menu saCmsMenuStats = {
.entries = saCmsMenuStatsEntries .entries = saCmsMenuStatsEntries
}; };
static const char * const saCmsBandNames[] = { static OSD_TAB_t saCmsEntBand = { &saCmsBand, 5, vtx58BandNames, NULL };
"--------",
"BOSCAM A",
"BOSCAM B",
"BOSCAM E",
"FATSHARK",
"RACEBAND",
};
static OSD_TAB_t saCmsEntBand = { &saCmsBand, 5, &saCmsBandNames[0], NULL }; static OSD_TAB_t saCmsEntChan = { &saCmsChan, 8, vtx58ChanNames, NULL };
static const char * const saCmsChanNames[] = { static OSD_TAB_t saCmsEntPower = { &saCmsPower, 4, saPowerNames};
"-", "1", "2", "3", "4", "5", "6", "7", "8",
};
static OSD_TAB_t saCmsEntChan = { &saCmsChan, 8, &saCmsChanNames[0], NULL };
static const char * const saCmsPowerNames[] = {
"---",
"25 ",
"200",
"500",
"800",
};
static OSD_TAB_t saCmsEntPower = { &saCmsPower, 4, saCmsPowerNames};
static OSD_UINT16_t saCmsEntFreqRef = { &saCmsFreqRef, 5600, 5900, 0 }; static OSD_UINT16_t saCmsEntFreqRef = { &saCmsFreqRef, 5600, 5900, 0 };

View File

@ -103,6 +103,7 @@
#define TELEMETRY_IBUS #define TELEMETRY_IBUS
#define USE_RX_MSP #define USE_RX_MSP
#define USE_SERIALRX_JETIEXBUS #define USE_SERIALRX_JETIEXBUS
#define VTX_COMMON
#define VTX_CONTROL #define VTX_CONTROL
#define VTX_SMARTAUDIO #define VTX_SMARTAUDIO
#define USE_SENSOR_NAMES #define USE_SENSOR_NAMES