mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-26 09:45:33 +03:00
Merge pull request #5461 from iNavFlight/de_vtx_refactor
VTX/CMS unification
This commit is contained in:
commit
01c5e668f3
37 changed files with 505 additions and 2198 deletions
|
@ -162,9 +162,7 @@ COMMON_SRC = \
|
||||||
cms/cms_menu_navigation.c \
|
cms/cms_menu_navigation.c \
|
||||||
cms/cms_menu_osd.c \
|
cms/cms_menu_osd.c \
|
||||||
cms/cms_menu_saveexit.c \
|
cms/cms_menu_saveexit.c \
|
||||||
cms/cms_menu_vtx_smartaudio.c \
|
cms/cms_menu_vtx.c \
|
||||||
cms/cms_menu_vtx_tramp.c \
|
|
||||||
cms/cms_menu_vtx_ffpv.c \
|
|
||||||
drivers/display_ug2864hsweg01.c \
|
drivers/display_ug2864hsweg01.c \
|
||||||
drivers/rangefinder/rangefinder_hcsr04.c \
|
drivers/rangefinder/rangefinder_hcsr04.c \
|
||||||
drivers/rangefinder/rangefinder_hcsr04_i2c.c \
|
drivers/rangefinder/rangefinder_hcsr04_i2c.c \
|
||||||
|
|
|
@ -50,13 +50,6 @@
|
||||||
#include "cms/cms_menu_battery.h"
|
#include "cms/cms_menu_battery.h"
|
||||||
#include "cms/cms_menu_misc.h"
|
#include "cms/cms_menu_misc.h"
|
||||||
|
|
||||||
// VTX supplied menus
|
|
||||||
|
|
||||||
#include "cms/cms_menu_vtx_smartaudio.h"
|
|
||||||
#include "cms/cms_menu_vtx_tramp.h"
|
|
||||||
#include "cms/cms_menu_vtx_ffpv.h"
|
|
||||||
|
|
||||||
|
|
||||||
// Info
|
// Info
|
||||||
|
|
||||||
static char infoGitRev[GIT_SHORT_REVISION_LENGTH + 1];
|
static char infoGitRev[GIT_SHORT_REVISION_LENGTH + 1];
|
||||||
|
@ -111,19 +104,8 @@ static const OSD_Entry menuFeaturesEntries[] =
|
||||||
#if defined(USE_NAV)
|
#if defined(USE_NAV)
|
||||||
OSD_SUBMENU_ENTRY("NAVIGATION", &cmsx_menuNavigation),
|
OSD_SUBMENU_ENTRY("NAVIGATION", &cmsx_menuNavigation),
|
||||||
#endif
|
#endif
|
||||||
#if defined(VTX) || defined(USE_RTC6705)
|
|
||||||
OSD_SUBMENU_ENTRY("VTX", &cmsx_menuVtx),
|
|
||||||
#endif // VTX || USE_RTC6705
|
|
||||||
#if defined(USE_VTX_CONTROL)
|
#if defined(USE_VTX_CONTROL)
|
||||||
#if defined(USE_VTX_SMARTAUDIO)
|
OSD_SUBMENU_ENTRY("VTX", &cmsx_menuVtxControl),
|
||||||
OSD_SUBMENU_ENTRY("VTX SA", &cmsx_menuVtxSmartAudio),
|
|
||||||
#endif
|
|
||||||
#if defined(USE_VTX_TRAMP)
|
|
||||||
OSD_SUBMENU_ENTRY("VTX TR", &cmsx_menuVtxTramp),
|
|
||||||
#endif
|
|
||||||
#if defined(USE_VTX_FFPV)
|
|
||||||
OSD_SUBMENU_ENTRY("VTX FFPV", &cmsx_menuVtxFFPV),
|
|
||||||
#endif
|
|
||||||
#endif // VTX_CONTROL
|
#endif // VTX_CONTROL
|
||||||
#ifdef USE_LED_STRIP
|
#ifdef USE_LED_STRIP
|
||||||
OSD_SUBMENU_ENTRY("LED STRIP", &cmsx_menuLedstrip),
|
OSD_SUBMENU_ENTRY("LED STRIP", &cmsx_menuLedstrip),
|
||||||
|
|
|
@ -15,132 +15,247 @@
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include <ctype.h>
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <ctype.h>
|
#include <string.h>
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#include "build/version.h"
|
#include "build/version.h"
|
||||||
|
|
||||||
|
#if defined(USE_CMS) && defined(USE_VTX_CONTROL)
|
||||||
|
|
||||||
|
#include "common/printf.h"
|
||||||
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "cms/cms.h"
|
#include "cms/cms.h"
|
||||||
#include "cms/cms_types.h"
|
#include "cms/cms_types.h"
|
||||||
#include "cms/cms_menu_vtx.h"
|
#include "cms/cms_menu_vtx.h"
|
||||||
|
|
||||||
#include "config/feature.h"
|
#include "drivers/vtx_common.h"
|
||||||
|
|
||||||
#ifdef USE_CMS
|
#include "fc/config.h"
|
||||||
|
|
||||||
#if defined(VTX) || defined(USE_RTC6705)
|
#include "io/vtx_string.h"
|
||||||
|
#include "io/vtx.h"
|
||||||
|
|
||||||
static bool featureRead = false;
|
|
||||||
static uint8_t cmsx_featureVtx = 0, cmsx_vtxBand, cmsx_vtxChannel;
|
|
||||||
|
|
||||||
static long cmsx_Vtx_FeatureRead(void)
|
// Config-time settings
|
||||||
{
|
static uint8_t vtxBand = 0;
|
||||||
if (!featureRead) {
|
static uint8_t vtxChan = 0;
|
||||||
cmsx_featureVtx = feature(FEATURE_VTX) ? 1 : 0;
|
static uint8_t vtxPower = 0;
|
||||||
featureRead = true;
|
static uint8_t vtxPitMode = 0;
|
||||||
}
|
|
||||||
|
|
||||||
return 0;
|
static const char * const vtxCmsPitModeNames[] = {
|
||||||
}
|
"---", "OFF", "ON "
|
||||||
|
|
||||||
static long cmsx_Vtx_FeatureWriteback(void)
|
|
||||||
{
|
|
||||||
if (cmsx_featureVtx)
|
|
||||||
featureSet(FEATURE_VTX);
|
|
||||||
else
|
|
||||||
featureClear(FEATURE_VTX);
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static const char * const vtxBandNames[] = {
|
|
||||||
"A",
|
|
||||||
"B",
|
|
||||||
"E",
|
|
||||||
"F",
|
|
||||||
"R",
|
|
||||||
};
|
};
|
||||||
|
|
||||||
static const OSD_TAB_t entryVtxBand = {&cmsx_vtxBand,4,&vtxBandNames[0]};
|
// Menus (these are not const because we update them at run-time )
|
||||||
static const OSD_UINT8_t entryVtxChannel = {&cmsx_vtxChannel, 1, 8, 1};
|
static OSD_TAB_t cms_Vtx_EntBand = { &vtxBand, VTX_SETTINGS_BAND_COUNT, vtx58BandNames };
|
||||||
|
static OSD_TAB_t cms_Vtx_EntChan = { &vtxChan, VTX_SETTINGS_CHANNEL_COUNT, vtx58ChannelNames };
|
||||||
|
static OSD_TAB_t cms_Vtx_EntPower = { &vtxPower, VTX_SETTINGS_POWER_COUNT, vtx58DefaultPowerNames };
|
||||||
|
static const OSD_TAB_t cms_Vtx_EntPitMode = { &vtxPitMode, 2, vtxCmsPitModeNames };
|
||||||
|
|
||||||
static void cmsx_Vtx_ConfigRead(void)
|
static long cms_Vtx_configPitMode(displayPort_t *pDisp, const void *self)
|
||||||
{
|
|
||||||
#ifdef VTX
|
|
||||||
cmsx_vtxBand = masterConfig.vtx_band;
|
|
||||||
cmsx_vtxChannel = masterConfig.vtx_channel + 1;
|
|
||||||
#endif // VTX
|
|
||||||
|
|
||||||
#ifdef USE_RTC6705
|
|
||||||
cmsx_vtxBand = masterConfig.vtx_channel / 8;
|
|
||||||
cmsx_vtxChannel = masterConfig.vtx_channel % 8 + 1;
|
|
||||||
#endif // USE_RTC6705
|
|
||||||
}
|
|
||||||
|
|
||||||
static void cmsx_Vtx_ConfigWriteback(void)
|
|
||||||
{
|
|
||||||
#ifdef VTX
|
|
||||||
masterConfig.vtx_band = cmsx_vtxBand;
|
|
||||||
masterConfig.vtx_channel = cmsx_vtxChannel - 1;
|
|
||||||
#endif // VTX
|
|
||||||
|
|
||||||
#ifdef USE_RTC6705
|
|
||||||
masterConfig.vtx_channel = cmsx_vtxBand * 8 + cmsx_vtxChannel - 1;
|
|
||||||
#endif // USE_RTC6705
|
|
||||||
}
|
|
||||||
|
|
||||||
static long cmsx_Vtx_onEnter(void)
|
|
||||||
{
|
|
||||||
cmsx_Vtx_FeatureRead();
|
|
||||||
cmsx_Vtx_ConfigRead();
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static long cmsx_Vtx_onExit(const OSD_Entry *self)
|
|
||||||
{
|
{
|
||||||
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
cmsx_Vtx_ConfigWriteback();
|
if (vtxPitMode == 0) {
|
||||||
|
vtxPitMode = 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Pit mode changes are immediate, without saving
|
||||||
|
vtxCommonSetPitMode(vtxCommonDevice(), vtxPitMode >= 2 ? 1 : 0);
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef VTX
|
static long cms_Vtx_configBand(displayPort_t *pDisp, const void *self)
|
||||||
static const OSD_UINT8_t entryVtxMode = {&masterConfig.vtx_mode, 0, 2, 1};
|
|
||||||
static const OSD_UINT16_t entryVtxMhz = {&masterConfig.vtx_mhz, 5600, 5950, 1};
|
|
||||||
#endif // VTX
|
|
||||||
|
|
||||||
static const OSD_Entry cmsx_menuVtxEntries[] =
|
|
||||||
{
|
{
|
||||||
OSD_LABEL_ENTRY("--- VTX ---"),
|
UNUSED(pDisp);
|
||||||
OSD_BOOL_ENTRY("ENABLED", &cmsx_featureVtx),
|
UNUSED(self);
|
||||||
#ifdef VTX
|
|
||||||
OSD_UINT8_ENTRY("VTX MODE", &entryVtxMode),
|
if (vtxBand == 0) {
|
||||||
OSD_UINT16_ENTRY("VTX MHZ", &entryVtxMhz),
|
vtxBand = 1;
|
||||||
#endif // VTX
|
}
|
||||||
OSD_TAB_ENTRY("BAND", &entryVtxBand),
|
return 0;
|
||||||
OSD_UINT8_ENTRY("CHANNEL", &entryVtxChannel),
|
}
|
||||||
#ifdef USE_RTC6705
|
|
||||||
OSD_BOOL_ENTRY("LOW POWER", &masterConfig.vtx_power),
|
static long cms_Vtx_configChan(displayPort_t *pDisp, const void *self)
|
||||||
#endif // USE_RTC6705
|
{
|
||||||
|
UNUSED(pDisp);
|
||||||
|
UNUSED(self);
|
||||||
|
|
||||||
|
if (vtxChan == 0) {
|
||||||
|
vtxChan = 1;
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cms_Vtx_configPower(displayPort_t *pDisp, const void *self)
|
||||||
|
{
|
||||||
|
UNUSED(pDisp);
|
||||||
|
UNUSED(self);
|
||||||
|
|
||||||
|
if (vtxPower == 0) {
|
||||||
|
vtxPower = 1;
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void cms_Vtx_initSettings(void)
|
||||||
|
{
|
||||||
|
vtxDevice_t * vtxDevice = vtxCommonDevice();
|
||||||
|
vtxDeviceCapability_t vtxDeviceCapability;
|
||||||
|
|
||||||
|
if (vtxCommonGetDeviceCapability(vtxDevice, &vtxDeviceCapability)) {
|
||||||
|
cms_Vtx_EntBand.max = vtxDeviceCapability.bandCount;
|
||||||
|
cms_Vtx_EntBand.names = (const char * const *)vtxDeviceCapability.bandNames;
|
||||||
|
|
||||||
|
cms_Vtx_EntChan.max = vtxDeviceCapability.channelCount;
|
||||||
|
cms_Vtx_EntChan.names = (const char * const *)vtxDeviceCapability.channelNames;
|
||||||
|
|
||||||
|
cms_Vtx_EntPower.max = vtxDeviceCapability.powerCount;
|
||||||
|
cms_Vtx_EntPower.names = (const char * const *)vtxDeviceCapability.powerNames;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
cms_Vtx_EntBand.max = VTX_SETTINGS_BAND_COUNT;
|
||||||
|
cms_Vtx_EntBand.names = vtx58BandNames;
|
||||||
|
|
||||||
|
cms_Vtx_EntChan.max = VTX_SETTINGS_CHANNEL_COUNT;
|
||||||
|
cms_Vtx_EntChan.names = vtx58ChannelNames;
|
||||||
|
|
||||||
|
cms_Vtx_EntPower.max = VTX_SETTINGS_POWER_COUNT;
|
||||||
|
cms_Vtx_EntPower.names = vtx58DefaultPowerNames;
|
||||||
|
}
|
||||||
|
|
||||||
|
vtxBand = vtxSettingsConfig()->band;
|
||||||
|
vtxChan = vtxSettingsConfig()->channel;
|
||||||
|
vtxPower = vtxSettingsConfig()->power;
|
||||||
|
|
||||||
|
// If device is ready - read actual PIT mode
|
||||||
|
if (vtxCommonDeviceIsReady(vtxDevice)) {
|
||||||
|
uint8_t onoff;
|
||||||
|
vtxCommonGetPitMode(vtxDevice, &onoff);
|
||||||
|
vtxPitMode = onoff ? 2 : 1;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
vtxPitMode = vtxSettingsConfig()->lowPowerDisarm ? 2 : 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cms_Vtx_onEnter(const OSD_Entry *self)
|
||||||
|
{
|
||||||
|
UNUSED(self);
|
||||||
|
cms_Vtx_initSettings();
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cms_Vtx_Commence(displayPort_t *pDisp, const void *self)
|
||||||
|
{
|
||||||
|
UNUSED(pDisp);
|
||||||
|
UNUSED(self);
|
||||||
|
|
||||||
|
vtxCommonSetBandAndChannel(vtxCommonDevice(), vtxBand, vtxChan);
|
||||||
|
vtxCommonSetPowerByIndex(vtxCommonDevice(), vtxPower);
|
||||||
|
vtxCommonSetPitMode(vtxCommonDevice(), vtxPitMode == 2 ? 1 : 0);
|
||||||
|
|
||||||
|
vtxSettingsConfigMutable()->band = vtxBand;
|
||||||
|
vtxSettingsConfigMutable()->channel = vtxChan;
|
||||||
|
vtxSettingsConfigMutable()->power = vtxPower;
|
||||||
|
vtxSettingsConfigMutable()->lowPowerDisarm = (vtxPitMode == 2 ? 1 : 0);
|
||||||
|
|
||||||
|
saveConfigAndNotify();
|
||||||
|
|
||||||
|
return MENU_CHAIN_BACK;
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool cms_Vtx_drawStatusString(char *buf, unsigned bufsize)
|
||||||
|
{
|
||||||
|
const char *defaultString = "-- ---- ----";
|
||||||
|
// bc ffff pppp
|
||||||
|
// 012345678901
|
||||||
|
|
||||||
|
if (bufsize < strlen(defaultString) + 1) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
strcpy(buf, defaultString);
|
||||||
|
|
||||||
|
vtxDevice_t * vtxDevice = vtxCommonDevice();
|
||||||
|
vtxDeviceOsdInfo_t osdInfo;
|
||||||
|
|
||||||
|
if (!vtxDevice || !vtxCommonGetOsdInfo(vtxDevice, &osdInfo) || !vtxCommonDeviceIsReady(vtxDevice)) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
buf[0] = osdInfo.bandLetter;
|
||||||
|
buf[1] = osdInfo.channelName[0];
|
||||||
|
buf[2] = ' ';
|
||||||
|
|
||||||
|
if (osdInfo.frequency)
|
||||||
|
tfp_sprintf(&buf[3], "%4d", osdInfo.frequency);
|
||||||
|
else
|
||||||
|
tfp_sprintf(&buf[3], "----");
|
||||||
|
|
||||||
|
if (osdInfo.powerIndex) {
|
||||||
|
// If OSD driver provides power in milliwatt - display MW, otherwise - power level
|
||||||
|
if (osdInfo.powerMilliwatt) {
|
||||||
|
tfp_sprintf(&buf[7], " %4d", osdInfo.powerMilliwatt);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
tfp_sprintf(&buf[7], " PL=%c", osdInfo.powerIndex);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
tfp_sprintf(&buf[7], " ----");
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
static const OSD_Entry cms_menuCommenceEntries[] =
|
||||||
|
{
|
||||||
|
OSD_LABEL_ENTRY("CONFIRM"),
|
||||||
|
OSD_FUNC_CALL_ENTRY("YES", cms_Vtx_Commence),
|
||||||
|
|
||||||
OSD_BACK_AND_END_ENTRY,
|
OSD_BACK_AND_END_ENTRY,
|
||||||
};
|
};
|
||||||
|
|
||||||
const CMS_Menu cmsx_menuVtx = {
|
static const CMS_Menu cms_menuCommence = {
|
||||||
|
#ifdef CMS_MENU_DEBUG
|
||||||
|
.GUARD_text = "XVTXTRC",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
#endif
|
||||||
|
.onEnter = NULL,
|
||||||
|
.onExit = NULL,
|
||||||
|
.onGlobalExit = NULL,
|
||||||
|
.entries = cms_menuCommenceEntries,
|
||||||
|
};
|
||||||
|
|
||||||
|
static const OSD_Entry cms_menuVtxEntries[] =
|
||||||
|
{
|
||||||
|
OSD_LABEL_ENTRY("--- VTX ---"),
|
||||||
|
OSD_LABEL_FUNC_DYN_ENTRY("", cms_Vtx_drawStatusString),
|
||||||
|
OSD_TAB_CALLBACK_ENTRY("PIT", cms_Vtx_configPitMode, &cms_Vtx_EntPitMode),
|
||||||
|
OSD_TAB_CALLBACK_ENTRY("BAND", cms_Vtx_configBand, &cms_Vtx_EntBand),
|
||||||
|
OSD_TAB_CALLBACK_ENTRY("CHAN", cms_Vtx_configChan, &cms_Vtx_EntChan),
|
||||||
|
OSD_TAB_CALLBACK_ENTRY("POWER", cms_Vtx_configPower, &cms_Vtx_EntPower),
|
||||||
|
|
||||||
|
OSD_SUBMENU_ENTRY("SET", &cms_menuCommence),
|
||||||
|
OSD_BACK_AND_END_ENTRY,
|
||||||
|
};
|
||||||
|
|
||||||
|
const CMS_Menu cmsx_menuVtxControl = {
|
||||||
#ifdef CMS_MENU_DEBUG
|
#ifdef CMS_MENU_DEBUG
|
||||||
.GUARD_text = "MENUVTX",
|
.GUARD_text = "MENUVTX",
|
||||||
.GUARD_type = OME_MENU,
|
.GUARD_type = OME_MENU,
|
||||||
#endif
|
#endif
|
||||||
.onEnter = cmsx_Vtx_onEnter,
|
.onEnter = cms_Vtx_onEnter,
|
||||||
.onExit= cmsx_Vtx_onExit,
|
.onExit = NULL,
|
||||||
.onGlobalExit = cmsx_Vtx_FeatureWriteback,
|
.onGlobalExit = NULL,
|
||||||
.entries = cmsx_menuVtxEntries
|
.entries = cms_menuVtxEntries
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // VTX || USE_RTC6705
|
|
||||||
#endif // CMS
|
#endif // CMS
|
||||||
|
|
|
@ -17,4 +17,4 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
extern const CMS_Menu cmsx_menuVtx;
|
extern const CMS_Menu cmsx_menuVtxControl;
|
||||||
|
|
|
@ -1,214 +0,0 @@
|
||||||
/*
|
|
||||||
* This file is part of Cleanflight and Betaflight.
|
|
||||||
*
|
|
||||||
* Cleanflight and Betaflight are free software. You can redistribute
|
|
||||||
* this software and/or modify this software under the terms of the
|
|
||||||
* GNU General Public License as published by the Free Software
|
|
||||||
* Foundation, either version 3 of the License, or (at your option)
|
|
||||||
* any later version.
|
|
||||||
*
|
|
||||||
* Cleanflight and Betaflight are distributed in the hope that they
|
|
||||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
|
||||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
|
||||||
* See the GNU General Public License for more details.
|
|
||||||
*
|
|
||||||
* You should have received a copy of the GNU General Public License
|
|
||||||
* along with this software.
|
|
||||||
*
|
|
||||||
* If not, see <http://www.gnu.org/licenses/>.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <ctype.h>
|
|
||||||
#include <stdbool.h>
|
|
||||||
#include <stdint.h>
|
|
||||||
#include <string.h>
|
|
||||||
|
|
||||||
#include "platform.h"
|
|
||||||
|
|
||||||
#if defined(USE_CMS) && defined(USE_VTX_FFPV)
|
|
||||||
|
|
||||||
#include "common/printf.h"
|
|
||||||
#include "common/utils.h"
|
|
||||||
|
|
||||||
#include "cms/cms.h"
|
|
||||||
#include "cms/cms_types.h"
|
|
||||||
|
|
||||||
#include "drivers/vtx_common.h"
|
|
||||||
|
|
||||||
#include "fc/config.h"
|
|
||||||
|
|
||||||
#include "io/vtx_string.h"
|
|
||||||
#include "io/vtx_ffpv24g.h"
|
|
||||||
#include "io/vtx.h"
|
|
||||||
|
|
||||||
static bool ffpvCmsDrawStatusString(char *buf, unsigned bufsize)
|
|
||||||
{
|
|
||||||
const char *defaultString = "- -- ---- ---";
|
|
||||||
// m bc ffff ppp
|
|
||||||
// 01234567890123
|
|
||||||
|
|
||||||
if (bufsize < strlen(defaultString) + 1) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
strcpy(buf, defaultString);
|
|
||||||
|
|
||||||
vtxDevice_t *vtxDevice = vtxCommonDevice();
|
|
||||||
if (!vtxDevice || vtxCommonGetDeviceType(vtxDevice) != VTXDEV_FFPV || !vtxCommonDeviceIsReady(vtxDevice)) {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
buf[0] = '*';
|
|
||||||
buf[1] = ' ';
|
|
||||||
buf[2] = ffpvBandLetters[ffpvGetRuntimeState()->band];
|
|
||||||
buf[3] = ffpvChannelNames[ffpvGetRuntimeState()->channel][0];
|
|
||||||
buf[4] = ' ';
|
|
||||||
|
|
||||||
tfp_sprintf(&buf[5], "%4d", ffpvGetRuntimeState()->frequency);
|
|
||||||
tfp_sprintf(&buf[9], " %3d", ffpvGetRuntimeState()->powerMilliwatt);
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t ffpvCmsBand = 1;
|
|
||||||
uint8_t ffpvCmsChan = 1;
|
|
||||||
uint16_t ffpvCmsFreqRef;
|
|
||||||
static uint8_t ffpvCmsPower = 1;
|
|
||||||
|
|
||||||
static const OSD_TAB_t ffpvCmsEntBand = { &ffpvCmsBand, VTX_FFPV_BAND_COUNT, ffpvBandNames };
|
|
||||||
static const OSD_TAB_t ffpvCmsEntChan = { &ffpvCmsChan, VTX_FFPV_CHANNEL_COUNT, ffpvChannelNames };
|
|
||||||
static const OSD_TAB_t ffpvCmsEntPower = { &ffpvCmsPower, VTX_FFPV_POWER_COUNT, ffpvPowerNames };
|
|
||||||
|
|
||||||
static void ffpvCmsUpdateFreqRef(void)
|
|
||||||
{
|
|
||||||
if (ffpvCmsBand > 0 && ffpvCmsChan > 0) {
|
|
||||||
ffpvCmsFreqRef = ffpvFrequencyTable[ffpvCmsBand - 1][ffpvCmsChan - 1];
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static long ffpvCmsConfigBand(displayPort_t *pDisp, const void *self)
|
|
||||||
{
|
|
||||||
UNUSED(pDisp);
|
|
||||||
UNUSED(self);
|
|
||||||
|
|
||||||
if (ffpvCmsBand == 0) {
|
|
||||||
// Bounce back
|
|
||||||
ffpvCmsBand = 1;
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
ffpvCmsUpdateFreqRef();
|
|
||||||
}
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static long ffpvCmsConfigChan(displayPort_t *pDisp, const void *self)
|
|
||||||
{
|
|
||||||
UNUSED(pDisp);
|
|
||||||
UNUSED(self);
|
|
||||||
|
|
||||||
if (ffpvCmsChan == 0) {
|
|
||||||
// Bounce back
|
|
||||||
ffpvCmsChan = 1;
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
ffpvCmsUpdateFreqRef();
|
|
||||||
}
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static long ffpvCmsConfigPower(displayPort_t *pDisp, const void *self)
|
|
||||||
{
|
|
||||||
UNUSED(pDisp);
|
|
||||||
UNUSED(self);
|
|
||||||
|
|
||||||
if (ffpvCmsPower == 0) {
|
|
||||||
// Bounce back
|
|
||||||
ffpvCmsPower = 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static long ffpvCmsCommence(displayPort_t *pDisp, const void *self)
|
|
||||||
{
|
|
||||||
UNUSED(pDisp);
|
|
||||||
UNUSED(self);
|
|
||||||
|
|
||||||
// call driver directly
|
|
||||||
ffpvSetBandAndChannel(ffpvCmsBand, ffpvCmsChan);
|
|
||||||
ffpvSetRFPowerByIndex(ffpvCmsPower);
|
|
||||||
|
|
||||||
// update'vtx_' settings
|
|
||||||
vtxSettingsConfigMutable()->band = ffpvCmsBand;
|
|
||||||
vtxSettingsConfigMutable()->channel = ffpvCmsChan;
|
|
||||||
vtxSettingsConfigMutable()->power = ffpvCmsPower;
|
|
||||||
vtxSettingsConfigMutable()->freq = ffpvFrequencyTable[ffpvCmsBand - 1][ffpvCmsChan - 1];
|
|
||||||
|
|
||||||
saveConfigAndNotify();
|
|
||||||
|
|
||||||
return MENU_CHAIN_BACK;
|
|
||||||
}
|
|
||||||
|
|
||||||
static void ffpvCmsInitSettings(void)
|
|
||||||
{
|
|
||||||
ffpvCmsBand = ffpvGetRuntimeState()->band;
|
|
||||||
ffpvCmsChan = ffpvGetRuntimeState()->channel;
|
|
||||||
ffpvCmsPower = ffpvGetRuntimeState()->powerIndex;
|
|
||||||
|
|
||||||
ffpvCmsUpdateFreqRef();
|
|
||||||
}
|
|
||||||
|
|
||||||
static long ffpvCmsOnEnter(const OSD_Entry *from)
|
|
||||||
{
|
|
||||||
UNUSED(from);
|
|
||||||
|
|
||||||
ffpvCmsInitSettings();
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static const OSD_Entry ffpvCmsMenuCommenceEntries[] =
|
|
||||||
{
|
|
||||||
OSD_LABEL_ENTRY("CONFIRM"),
|
|
||||||
OSD_FUNC_CALL_ENTRY("YES", ffpvCmsCommence),
|
|
||||||
|
|
||||||
OSD_BACK_AND_END_ENTRY,
|
|
||||||
};
|
|
||||||
|
|
||||||
static const CMS_Menu ffpvCmsMenuCommence = {
|
|
||||||
#ifdef CMS_MENU_DEBUG
|
|
||||||
.GUARD_text = "XVTXTRC",
|
|
||||||
.GUARD_type = OME_MENU,
|
|
||||||
#endif
|
|
||||||
.onEnter = NULL,
|
|
||||||
.onExit = NULL,
|
|
||||||
.onGlobalExit = NULL,
|
|
||||||
.entries = ffpvCmsMenuCommenceEntries,
|
|
||||||
};
|
|
||||||
|
|
||||||
static const OSD_Entry ffpvMenuEntries[] =
|
|
||||||
{
|
|
||||||
OSD_LABEL_ENTRY("- TRAMP -"),
|
|
||||||
|
|
||||||
OSD_LABEL_FUNC_DYN_ENTRY("", ffpvCmsDrawStatusString),
|
|
||||||
OSD_TAB_CALLBACK_ENTRY("BAND", ffpvCmsConfigBand, &ffpvCmsEntBand),
|
|
||||||
OSD_TAB_CALLBACK_ENTRY("CHAN", ffpvCmsConfigChan, &ffpvCmsEntChan),
|
|
||||||
OSD_UINT16_RO_ENTRY("(FREQ)", &ffpvCmsFreqRef),
|
|
||||||
OSD_TAB_CALLBACK_ENTRY("POWER", ffpvCmsConfigPower, &ffpvCmsEntPower),
|
|
||||||
OSD_SUBMENU_ENTRY("SET", &ffpvCmsMenuCommence),
|
|
||||||
|
|
||||||
OSD_BACK_AND_END_ENTRY,
|
|
||||||
};
|
|
||||||
|
|
||||||
const CMS_Menu cmsx_menuVtxFFPV = {
|
|
||||||
#ifdef CMS_MENU_DEBUG
|
|
||||||
.GUARD_text = "XVTXTR",
|
|
||||||
.GUARD_type = OME_MENU,
|
|
||||||
#endif
|
|
||||||
.onEnter = ffpvCmsOnEnter,
|
|
||||||
.onExit = NULL,
|
|
||||||
.onGlobalExit = NULL,
|
|
||||||
.entries = ffpvMenuEntries,
|
|
||||||
};
|
|
||||||
#endif
|
|
|
@ -1,23 +0,0 @@
|
||||||
/*
|
|
||||||
* 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 "cms/cms.h"
|
|
||||||
#include "cms/cms_types.h"
|
|
||||||
|
|
||||||
extern const CMS_Menu cmsx_menuVtxFFPV;
|
|
|
@ -1,710 +0,0 @@
|
||||||
/*
|
|
||||||
* This file is part of Cleanflight and Betaflight.
|
|
||||||
*
|
|
||||||
* Cleanflight and Betaflight are free software. You can redistribute
|
|
||||||
* this software and/or modify this software under the terms of the
|
|
||||||
* GNU General Public License as published by the Free Software
|
|
||||||
* Foundation, either version 3 of the License, or (at your option)
|
|
||||||
* any later version.
|
|
||||||
*
|
|
||||||
* Cleanflight and Betaflight are distributed in the hope that they
|
|
||||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
|
||||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
|
||||||
* See the GNU General Public License for more details.
|
|
||||||
*
|
|
||||||
* You should have received a copy of the GNU General Public License
|
|
||||||
* along with this software.
|
|
||||||
*
|
|
||||||
* If not, see <http://www.gnu.org/licenses/>.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <stdbool.h>
|
|
||||||
#include <stdint.h>
|
|
||||||
#include <ctype.h>
|
|
||||||
#include <string.h>
|
|
||||||
|
|
||||||
#include "platform.h"
|
|
||||||
|
|
||||||
#if defined(USE_CMS) && defined(USE_VTX_SMARTAUDIO)
|
|
||||||
|
|
||||||
#include "common/log.h"
|
|
||||||
#include "common/printf.h"
|
|
||||||
#include "common/utils.h"
|
|
||||||
|
|
||||||
#include "cms/cms.h"
|
|
||||||
#include "cms/cms_types.h"
|
|
||||||
#include "cms/cms_menu_vtx_smartaudio.h"
|
|
||||||
|
|
||||||
#include "drivers/vtx_common.h"
|
|
||||||
|
|
||||||
#include "fc/config.h"
|
|
||||||
|
|
||||||
#include "io/vtx_string.h"
|
|
||||||
#include "io/vtx_smartaudio.h"
|
|
||||||
#include "io/vtx.h"
|
|
||||||
|
|
||||||
// Interface to CMS
|
|
||||||
|
|
||||||
// Operational Model and RF modes (CMS)
|
|
||||||
|
|
||||||
#define SACMS_OPMODEL_UNDEF 0 // Not known yet
|
|
||||||
#define SACMS_OPMODEL_FREE 1 // Freestyle model: Power up transmitting
|
|
||||||
#define SACMS_OPMODEL_RACE 2 // Race model: Power up in pit mode
|
|
||||||
|
|
||||||
uint8_t saCmsOpmodel = SACMS_OPMODEL_UNDEF;
|
|
||||||
|
|
||||||
#define SACMS_TXMODE_NODEF 0
|
|
||||||
#define SACMS_TXMODE_PIT_OUTRANGE 1
|
|
||||||
#define SACMS_TXMODE_PIT_INRANGE 2
|
|
||||||
#define SACMS_TXMODE_ACTIVE 3
|
|
||||||
|
|
||||||
uint8_t saCmsRFState; // RF state; ACTIVE, PIR, POR XXX Not currently used
|
|
||||||
|
|
||||||
uint8_t saCmsBand = 0;
|
|
||||||
uint8_t saCmsChan = 0;
|
|
||||||
uint8_t saCmsPower = 0;
|
|
||||||
|
|
||||||
// Frequency derived from channel table (used for reference in band/channel mode)
|
|
||||||
uint16_t saCmsFreqRef = 0;
|
|
||||||
|
|
||||||
uint16_t saCmsDeviceFreq = 0;
|
|
||||||
|
|
||||||
uint8_t saCmsDeviceStatus = 0;
|
|
||||||
uint8_t saCmsPower;
|
|
||||||
uint8_t saCmsPitFMode; // Undef(0), In-Range(1) or Out-Range(2)
|
|
||||||
|
|
||||||
uint8_t saCmsFselMode; // Channel(0) or User defined(1)
|
|
||||||
uint8_t saCmsFselModeNew; // Channel(0) or User defined(1)
|
|
||||||
|
|
||||||
uint16_t saCmsORFreq = 0; // POR frequency
|
|
||||||
uint16_t saCmsORFreqNew; // POR frequency
|
|
||||||
|
|
||||||
uint16_t saCmsUserFreq = 0; // User defined frequency
|
|
||||||
uint16_t saCmsUserFreqNew; // User defined frequency
|
|
||||||
|
|
||||||
static long saCmsConfigOpmodelByGvar(displayPort_t *, const void *self);
|
|
||||||
static long saCmsConfigPitFModeByGvar(displayPort_t *, const void *self);
|
|
||||||
static long saCmsConfigBandByGvar(displayPort_t *, const void *self);
|
|
||||||
static long saCmsConfigChanByGvar(displayPort_t *, const void *self);
|
|
||||||
static long saCmsConfigPowerByGvar(displayPort_t *, const void *self);
|
|
||||||
|
|
||||||
static bool saCmsUpdateCopiedState(void)
|
|
||||||
{
|
|
||||||
if (saDevice.version == 0)
|
|
||||||
return false;
|
|
||||||
|
|
||||||
if (saCmsDeviceStatus == 0 && saDevice.version != 0)
|
|
||||||
saCmsDeviceStatus = saDevice.version;
|
|
||||||
if (saCmsORFreq == 0 && saDevice.orfreq != 0)
|
|
||||||
saCmsORFreq = saDevice.orfreq;
|
|
||||||
if (saCmsUserFreq == 0 && saDevice.freq != 0)
|
|
||||||
saCmsUserFreq = saDevice.freq;
|
|
||||||
|
|
||||||
if (saDevice.version == 2) {
|
|
||||||
if (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE)
|
|
||||||
saCmsPitFMode = 1;
|
|
||||||
else
|
|
||||||
saCmsPitFMode = 0;
|
|
||||||
}
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
static bool saCmsDrawStatusString(char *buf, unsigned bufsize)
|
|
||||||
{
|
|
||||||
const char *defaultString = "- -- ---- ---";
|
|
||||||
// m bc ffff ppp
|
|
||||||
// 0123456789012
|
|
||||||
|
|
||||||
if (bufsize < strlen(defaultString) + 1) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
strcpy(buf, defaultString);
|
|
||||||
|
|
||||||
if (!saCmsUpdateCopiedState()) {
|
|
||||||
// VTX is not ready
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
buf[0] = "-FR"[saCmsOpmodel];
|
|
||||||
|
|
||||||
if (saCmsFselMode == 0) {
|
|
||||||
buf[2] = "ABEFR"[saDevice.channel / 8];
|
|
||||||
buf[3] = '1' + (saDevice.channel % 8);
|
|
||||||
} else {
|
|
||||||
buf[2] = 'U';
|
|
||||||
buf[3] = 'F';
|
|
||||||
}
|
|
||||||
|
|
||||||
if ((saDevice.mode & SA_MODE_GET_PITMODE)
|
|
||||||
&& (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE))
|
|
||||||
tfp_sprintf(&buf[5], "%4d", saDevice.orfreq);
|
|
||||||
else if (saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ)
|
|
||||||
tfp_sprintf(&buf[5], "%4d", saDevice.freq);
|
|
||||||
else
|
|
||||||
tfp_sprintf(&buf[5], "%4d",
|
|
||||||
vtx58frequencyTable[saDevice.channel / 8][saDevice.channel % 8]);
|
|
||||||
|
|
||||||
buf[9] = ' ';
|
|
||||||
|
|
||||||
if (saDevice.mode & SA_MODE_GET_PITMODE) {
|
|
||||||
buf[10] = 'P';
|
|
||||||
if (saDevice.mode & SA_MODE_GET_IN_RANGE_PITMODE) {
|
|
||||||
buf[11] = 'I';
|
|
||||||
} else {
|
|
||||||
buf[11] = 'O';
|
|
||||||
}
|
|
||||||
buf[12] = 'R';
|
|
||||||
buf[13] = 0;
|
|
||||||
} else {
|
|
||||||
tfp_sprintf(&buf[10], "%3d", (saDevice.version == 2) ? saPowerTable[saDevice.power].rfpower : saPowerTable[saDacToPowerIndex(saDevice.power)].rfpower);
|
|
||||||
}
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
void saCmsUpdate(void)
|
|
||||||
{
|
|
||||||
// XXX Take care of pit mode update somewhere???
|
|
||||||
if (saCmsOpmodel == SACMS_OPMODEL_UNDEF) {
|
|
||||||
// This is a first valid response to GET_SETTINGS.
|
|
||||||
saCmsOpmodel = (saDevice.mode & SA_MODE_GET_PITMODE) ? SACMS_OPMODEL_RACE : SACMS_OPMODEL_FREE;
|
|
||||||
|
|
||||||
saCmsFselMode = (saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ) ? 1 : 0;
|
|
||||||
|
|
||||||
saCmsBand = vtxSettingsConfig()->band;
|
|
||||||
saCmsChan = vtxSettingsConfig()->channel;
|
|
||||||
saCmsFreqRef = vtxSettingsConfig()->freq;
|
|
||||||
saCmsDeviceFreq = saCmsFreqRef;
|
|
||||||
|
|
||||||
if ((saDevice.mode & SA_MODE_GET_PITMODE) == 0) {
|
|
||||||
saCmsRFState = SACMS_TXMODE_ACTIVE;
|
|
||||||
} else if (saDevice.mode & SA_MODE_GET_IN_RANGE_PITMODE) {
|
|
||||||
saCmsRFState = SACMS_TXMODE_PIT_INRANGE;
|
|
||||||
} else {
|
|
||||||
saCmsRFState = SACMS_TXMODE_PIT_OUTRANGE;
|
|
||||||
}
|
|
||||||
|
|
||||||
saCmsPower = vtxSettingsConfig()->power;
|
|
||||||
|
|
||||||
// if user-freq mode then track possible change
|
|
||||||
if (saCmsFselMode && vtxSettingsConfig()->freq) {
|
|
||||||
saCmsUserFreq = vtxSettingsConfig()->freq;
|
|
||||||
}
|
|
||||||
|
|
||||||
saCmsFselModeNew = saCmsFselMode; //init mode for menu
|
|
||||||
}
|
|
||||||
|
|
||||||
saCmsUpdateCopiedState();
|
|
||||||
}
|
|
||||||
|
|
||||||
void saCmsResetOpmodel()
|
|
||||||
{
|
|
||||||
// trigger data refresh in 'saCmsUpdate()'
|
|
||||||
saCmsOpmodel = SACMS_OPMODEL_UNDEF;
|
|
||||||
}
|
|
||||||
|
|
||||||
static long saCmsConfigBandByGvar(displayPort_t *pDisp, const void *self)
|
|
||||||
{
|
|
||||||
UNUSED(pDisp);
|
|
||||||
UNUSED(self);
|
|
||||||
|
|
||||||
if (saDevice.version == 0) {
|
|
||||||
// Bounce back; not online yet
|
|
||||||
saCmsBand = 0;
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (saCmsBand == 0) {
|
|
||||||
// Bouce back, no going back to undef state
|
|
||||||
saCmsBand = 1;
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred)
|
|
||||||
saSetBandAndChannel(saCmsBand - 1, saCmsChan - 1);
|
|
||||||
|
|
||||||
saCmsFreqRef = vtx58frequencyTable[saCmsBand - 1][saCmsChan - 1];
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static long saCmsConfigChanByGvar(displayPort_t *pDisp, const void *self)
|
|
||||||
{
|
|
||||||
UNUSED(pDisp);
|
|
||||||
UNUSED(self);
|
|
||||||
|
|
||||||
if (saDevice.version == 0) {
|
|
||||||
// Bounce back; not online yet
|
|
||||||
saCmsChan = 0;
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (saCmsChan == 0) {
|
|
||||||
// Bounce back; no going back to undef state
|
|
||||||
saCmsChan = 1;
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred)
|
|
||||||
saSetBandAndChannel(saCmsBand - 1, saCmsChan - 1);
|
|
||||||
|
|
||||||
saCmsFreqRef = vtx58frequencyTable[saCmsBand - 1][saCmsChan - 1];
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static long saCmsConfigPowerByGvar(displayPort_t *pDisp, const void *self)
|
|
||||||
{
|
|
||||||
UNUSED(pDisp);
|
|
||||||
UNUSED(self);
|
|
||||||
|
|
||||||
if (saDevice.version == 0) {
|
|
||||||
// Bounce back; not online yet
|
|
||||||
saCmsPower = 0;
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (saCmsPower == 0) {
|
|
||||||
// Bouce back; no going back to undef state
|
|
||||||
saCmsPower = 1;
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (saCmsOpmodel == SACMS_OPMODEL_FREE && !saDeferred) {
|
|
||||||
vtxSettingsConfigMutable()->power = saCmsPower;
|
|
||||||
}
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static long saCmsConfigPitFModeByGvar(displayPort_t *pDisp, const void *self)
|
|
||||||
{
|
|
||||||
UNUSED(pDisp);
|
|
||||||
UNUSED(self);
|
|
||||||
|
|
||||||
if (saDevice.version == 1) {
|
|
||||||
// V1 device doesn't support PIT mode; bounce back.
|
|
||||||
saCmsPitFMode = 0;
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
LOG_D(VTX, "saCmsConfigPitFmodeByGbar: saCmsPitFMode %d", saCmsPitFMode);
|
|
||||||
|
|
||||||
if (saCmsPitFMode == 0) {
|
|
||||||
// Bounce back
|
|
||||||
saCmsPitFMode = 1;
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (saCmsPitFMode == 1) {
|
|
||||||
saSetMode(SA_MODE_SET_IN_RANGE_PITMODE);
|
|
||||||
} else {
|
|
||||||
saSetMode(SA_MODE_SET_OUT_RANGE_PITMODE);
|
|
||||||
}
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static long saCmsConfigFreqModeByGvar(displayPort_t *pDisp, const void *self); // Forward
|
|
||||||
|
|
||||||
static long saCmsConfigOpmodelByGvar(displayPort_t *pDisp, const void *self)
|
|
||||||
{
|
|
||||||
UNUSED(pDisp);
|
|
||||||
UNUSED(self);
|
|
||||||
|
|
||||||
if (saDevice.version == 1) {
|
|
||||||
if (saCmsOpmodel != SACMS_OPMODEL_FREE)
|
|
||||||
saCmsOpmodel = SACMS_OPMODEL_FREE;
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t opmodel = saCmsOpmodel;
|
|
||||||
|
|
||||||
LOG_D(VTX, "saCmsConfigOpmodelByGvar: opmodel %d", opmodel);
|
|
||||||
|
|
||||||
if (opmodel == SACMS_OPMODEL_FREE) {
|
|
||||||
// VTX should power up transmitting.
|
|
||||||
// Turn off In-Range and Out-Range bits
|
|
||||||
saSetMode(0);
|
|
||||||
} else if (opmodel == SACMS_OPMODEL_RACE) {
|
|
||||||
// VTX should power up in pit mode.
|
|
||||||
// Default PitFMode is in-range to prevent users without
|
|
||||||
// out-range receivers from getting blinded.
|
|
||||||
saCmsPitFMode = 0;
|
|
||||||
saCmsConfigPitFModeByGvar(pDisp, self);
|
|
||||||
|
|
||||||
// Direct frequency mode is not available in RACE opmodel
|
|
||||||
saCmsFselModeNew = 0;
|
|
||||||
saCmsConfigFreqModeByGvar(pDisp, self);
|
|
||||||
} else {
|
|
||||||
// Trying to go back to unknown state; bounce back
|
|
||||||
saCmsOpmodel = SACMS_OPMODEL_UNDEF + 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
#ifdef USE_EXTENDED_CMS_MENUS
|
|
||||||
static const char * const saCmsDeviceStatusNames[] = {
|
|
||||||
"OFFL",
|
|
||||||
"ONL V1",
|
|
||||||
"ONL V2",
|
|
||||||
};
|
|
||||||
|
|
||||||
static const OSD_TAB_t saCmsEntOnline = { &saCmsDeviceStatus, 2, saCmsDeviceStatusNames };
|
|
||||||
|
|
||||||
static const OSD_Entry saCmsMenuStatsEntries[] = {
|
|
||||||
OSD_LABEL_ENTRY("- SA STATS -"),
|
|
||||||
|
|
||||||
OSD_TAB_DYN_ENTRY("STATUS", &saCmsEntOnline),
|
|
||||||
OSD_UINT16_RO_ENTRY("BAUDRATE", &sa_smartbaud),
|
|
||||||
OSD_UINT16_RO_ENTRY("SENT", &saStat.pktsent),
|
|
||||||
OSD_UINT16_RO_ENTRY("RCVD", &saStat.pktrcvd),
|
|
||||||
OSD_UINT16_RO_ENTRY("BADPRE", &saStat.badpre),
|
|
||||||
OSD_UINT16_RO_ENTRY("BADLEN", &saStat.badlen),
|
|
||||||
OSD_UINT16_RO_ENTRY("CRCERR", &saStat.crc),
|
|
||||||
OSD_UINT16_RO_ENTRY("OOOERR", &saStat.ooopresp),
|
|
||||||
|
|
||||||
OSD_BACK_AND_END_ENTRY,
|
|
||||||
};
|
|
||||||
|
|
||||||
static const CMS_Menu saCmsMenuStats = {
|
|
||||||
#ifdef CMS_MENU_DEBUG
|
|
||||||
.GUARD_text = "XSAST",
|
|
||||||
.GUARD_type = OME_MENU,
|
|
||||||
#endif
|
|
||||||
.onEnter = NULL,
|
|
||||||
.onExit = NULL,
|
|
||||||
.onGlobalExit = NULL,
|
|
||||||
.entries = saCmsMenuStatsEntries
|
|
||||||
};
|
|
||||||
#endif /* USE_EXTENDED_CMS_MENUS */
|
|
||||||
|
|
||||||
static const OSD_TAB_t saCmsEntBand = { &saCmsBand, VTX_SMARTAUDIO_BAND_COUNT, vtx58BandNames };
|
|
||||||
|
|
||||||
static const OSD_TAB_t saCmsEntChan = { &saCmsChan, VTX_SMARTAUDIO_CHANNEL_COUNT, vtx58ChannelNames };
|
|
||||||
|
|
||||||
static const OSD_TAB_t saCmsEntPower = { &saCmsPower, VTX_SMARTAUDIO_POWER_COUNT, saPowerNames};
|
|
||||||
|
|
||||||
static const char * const saCmsOpmodelNames[] = {
|
|
||||||
"----",
|
|
||||||
"FREE",
|
|
||||||
"RACE",
|
|
||||||
};
|
|
||||||
|
|
||||||
static const char * const saCmsFselModeNames[] = {
|
|
||||||
"CHAN",
|
|
||||||
"USER"
|
|
||||||
};
|
|
||||||
|
|
||||||
static const char * const saCmsPitFModeNames[] = {
|
|
||||||
"---",
|
|
||||||
"PIR",
|
|
||||||
"POR"
|
|
||||||
};
|
|
||||||
|
|
||||||
static const OSD_TAB_t saCmsEntPitFMode = { &saCmsPitFMode, 1, saCmsPitFModeNames };
|
|
||||||
|
|
||||||
static long sacms_SetupTopMenu(const OSD_Entry *from); // Forward
|
|
||||||
|
|
||||||
static long saCmsConfigFreqModeByGvar(displayPort_t *pDisp, const void *self)
|
|
||||||
{
|
|
||||||
UNUSED(pDisp);
|
|
||||||
UNUSED(self);
|
|
||||||
|
|
||||||
// if trying to do user frequency mode in RACE opmodel then
|
|
||||||
// revert because user-freq only available in FREE opmodel
|
|
||||||
if (saCmsFselModeNew != 0 && saCmsOpmodel != SACMS_OPMODEL_FREE) {
|
|
||||||
saCmsFselModeNew = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
// don't call 'saSetBandAndChannel()' / 'saSetFreq()' here,
|
|
||||||
// wait until SET / 'saCmsCommence()' is activated
|
|
||||||
|
|
||||||
sacms_SetupTopMenu(NULL);
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static long saCmsCommence(displayPort_t *pDisp, const void *self)
|
|
||||||
{
|
|
||||||
UNUSED(pDisp);
|
|
||||||
UNUSED(self);
|
|
||||||
|
|
||||||
const vtxSettingsConfig_t prevSettings = {
|
|
||||||
.band = vtxSettingsConfig()->band,
|
|
||||||
.channel = vtxSettingsConfig()->channel,
|
|
||||||
.freq = vtxSettingsConfig()->freq,
|
|
||||||
.power = vtxSettingsConfig()->power,
|
|
||||||
.lowPowerDisarm = vtxSettingsConfig()->lowPowerDisarm,
|
|
||||||
};
|
|
||||||
vtxSettingsConfig_t newSettings = prevSettings;
|
|
||||||
|
|
||||||
if (saCmsOpmodel == SACMS_OPMODEL_RACE) {
|
|
||||||
// Race model
|
|
||||||
// Setup band, freq and power.
|
|
||||||
|
|
||||||
newSettings.band = saCmsBand;
|
|
||||||
newSettings.channel = saCmsChan;
|
|
||||||
newSettings.freq = vtx58_Bandchan2Freq(saCmsBand, saCmsChan);
|
|
||||||
// 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 (saCmsFselModeNew == 0) {
|
|
||||||
newSettings.band = saCmsBand;
|
|
||||||
newSettings.channel = saCmsChan;
|
|
||||||
newSettings.freq = vtx58_Bandchan2Freq(saCmsBand, saCmsChan);
|
|
||||||
} else {
|
|
||||||
saSetMode(0); //make sure FREE mode is setup
|
|
||||||
newSettings.band = 0;
|
|
||||||
newSettings.freq = saCmsUserFreq;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
newSettings.power = saCmsPower;
|
|
||||||
|
|
||||||
if (memcmp(&prevSettings, &newSettings, sizeof(vtxSettingsConfig_t))) {
|
|
||||||
vtxSettingsConfigMutable()->band = newSettings.band;
|
|
||||||
vtxSettingsConfigMutable()->channel = newSettings.channel;
|
|
||||||
vtxSettingsConfigMutable()->power = newSettings.power;
|
|
||||||
vtxSettingsConfigMutable()->freq = newSettings.freq;
|
|
||||||
saveConfigAndNotify();
|
|
||||||
}
|
|
||||||
|
|
||||||
return MENU_CHAIN_BACK;
|
|
||||||
}
|
|
||||||
|
|
||||||
static long saCmsSetPORFreqOnEnter(const OSD_Entry *from)
|
|
||||||
{
|
|
||||||
UNUSED(from);
|
|
||||||
|
|
||||||
if (saDevice.version == 1)
|
|
||||||
return MENU_CHAIN_BACK;
|
|
||||||
|
|
||||||
saCmsORFreqNew = saCmsORFreq;
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static long saCmsSetPORFreq(displayPort_t *pDisp, const void *self)
|
|
||||||
{
|
|
||||||
UNUSED(pDisp);
|
|
||||||
UNUSED(self);
|
|
||||||
|
|
||||||
saSetPitFreq(saCmsORFreqNew);
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static char *saCmsORFreqGetString(void)
|
|
||||||
{
|
|
||||||
static char pbuf[5];
|
|
||||||
|
|
||||||
tfp_sprintf(pbuf, "%4d", saCmsORFreq);
|
|
||||||
|
|
||||||
return pbuf;
|
|
||||||
}
|
|
||||||
|
|
||||||
static char *saCmsUserFreqGetString(void)
|
|
||||||
{
|
|
||||||
static char pbuf[5];
|
|
||||||
|
|
||||||
tfp_sprintf(pbuf, "%4d", saCmsUserFreq);
|
|
||||||
|
|
||||||
return pbuf;
|
|
||||||
}
|
|
||||||
|
|
||||||
static long saCmsSetUserFreqOnEnter(const OSD_Entry *from)
|
|
||||||
{
|
|
||||||
UNUSED(from);
|
|
||||||
|
|
||||||
saCmsUserFreqNew = saCmsUserFreq;
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static long saCmsConfigUserFreq(displayPort_t *pDisp, const void *self)
|
|
||||||
{
|
|
||||||
UNUSED(pDisp);
|
|
||||||
UNUSED(self);
|
|
||||||
|
|
||||||
saCmsUserFreq = saCmsUserFreqNew;
|
|
||||||
|
|
||||||
return MENU_CHAIN_BACK;
|
|
||||||
}
|
|
||||||
|
|
||||||
static const OSD_Entry saCmsMenuPORFreqEntries[] =
|
|
||||||
{
|
|
||||||
OSD_LABEL_ENTRY("- POR FREQ -"),
|
|
||||||
|
|
||||||
OSD_UINT16_RO_ENTRY("CUR FREQ", &saCmsORFreq),
|
|
||||||
OSD_UINT16_ENTRY("NEW FREQ", (&(const OSD_UINT16_t){ &saCmsORFreqNew, 5000, 5900, 1 })),
|
|
||||||
OSD_FUNC_CALL_ENTRY("SET", saCmsSetPORFreq),
|
|
||||||
|
|
||||||
OSD_BACK_AND_END_ENTRY,
|
|
||||||
};
|
|
||||||
|
|
||||||
static const CMS_Menu saCmsMenuPORFreq =
|
|
||||||
{
|
|
||||||
#ifdef CMS_MENU_DEBUG
|
|
||||||
.GUARD_text = "XSAPOR",
|
|
||||||
.GUARD_type = OME_MENU,
|
|
||||||
#endif
|
|
||||||
.onEnter = saCmsSetPORFreqOnEnter,
|
|
||||||
.onExit = NULL,
|
|
||||||
.onGlobalExit = NULL,
|
|
||||||
.entries = saCmsMenuPORFreqEntries,
|
|
||||||
};
|
|
||||||
|
|
||||||
static const OSD_Entry saCmsMenuUserFreqEntries[] =
|
|
||||||
{
|
|
||||||
OSD_LABEL_ENTRY("- USER FREQ -"),
|
|
||||||
|
|
||||||
OSD_UINT16_RO_ENTRY("CUR FREQ", &saCmsUserFreq),
|
|
||||||
OSD_UINT16_ENTRY("NEW FREQ", (&(const OSD_UINT16_t){ &saCmsUserFreqNew, 5000, 5900, 1 })),
|
|
||||||
OSD_FUNC_CALL_ENTRY("SET", saCmsConfigUserFreq),
|
|
||||||
|
|
||||||
OSD_BACK_AND_END_ENTRY,
|
|
||||||
};
|
|
||||||
|
|
||||||
static const CMS_Menu saCmsMenuUserFreq =
|
|
||||||
{
|
|
||||||
#ifdef CMS_MENU_DEBUG
|
|
||||||
.GUARD_text = "XSAUFQ",
|
|
||||||
.GUARD_type = OME_MENU,
|
|
||||||
#endif
|
|
||||||
.onEnter = saCmsSetUserFreqOnEnter,
|
|
||||||
.onExit = NULL,
|
|
||||||
.onGlobalExit = NULL,
|
|
||||||
.entries = saCmsMenuUserFreqEntries,
|
|
||||||
};
|
|
||||||
|
|
||||||
static const OSD_TAB_t saCmsEntFselMode = { &saCmsFselModeNew, 1, saCmsFselModeNames };
|
|
||||||
|
|
||||||
static const OSD_Entry saCmsMenuConfigEntries[] =
|
|
||||||
{
|
|
||||||
OSD_LABEL_ENTRY("- SA CONFIG -"),
|
|
||||||
|
|
||||||
{ "OP MODEL", {.func = saCmsConfigOpmodelByGvar}, &(const OSD_TAB_t){ &saCmsOpmodel, 2, saCmsOpmodelNames }, OME_TAB, DYNAMIC },
|
|
||||||
{ "FSEL MODE", {.func = saCmsConfigFreqModeByGvar}, &saCmsEntFselMode, OME_TAB, DYNAMIC },
|
|
||||||
OSD_TAB_CALLBACK_ENTRY("PIT FMODE", saCmsConfigPitFModeByGvar, &saCmsEntPitFMode),
|
|
||||||
{ "POR FREQ", {.menufunc = saCmsORFreqGetString}, (void *)&saCmsMenuPORFreq, OME_Submenu, OPTSTRING },
|
|
||||||
#ifdef USE_EXTENDED_CMS_MENUS
|
|
||||||
OSD_SUBMENU_ENTRY("STATX", &saCmsMenuStats),
|
|
||||||
#endif /* USE_EXTENDED_CMS_MENUS */
|
|
||||||
|
|
||||||
OSD_BACK_AND_END_ENTRY,
|
|
||||||
};
|
|
||||||
|
|
||||||
static const CMS_Menu saCmsMenuConfig = {
|
|
||||||
#ifdef CMS_MENU_DEBUG
|
|
||||||
.GUARD_text = "XSACFG",
|
|
||||||
.GUARD_type = OME_MENU,
|
|
||||||
#endif
|
|
||||||
.onEnter = NULL,
|
|
||||||
.onExit = NULL,
|
|
||||||
.onGlobalExit = NULL,
|
|
||||||
.entries = saCmsMenuConfigEntries
|
|
||||||
};
|
|
||||||
|
|
||||||
static const OSD_Entry saCmsMenuCommenceEntries[] =
|
|
||||||
{
|
|
||||||
OSD_LABEL_ENTRY("CONFIRM"),
|
|
||||||
OSD_FUNC_CALL_ENTRY("YES", saCmsCommence),
|
|
||||||
|
|
||||||
OSD_BACK_AND_END_ENTRY,
|
|
||||||
};
|
|
||||||
|
|
||||||
static const CMS_Menu saCmsMenuCommence = {
|
|
||||||
#ifdef CMS_MENU_DEBUG
|
|
||||||
.GUARD_text = "XVTXCOM",
|
|
||||||
.GUARD_type = OME_MENU,
|
|
||||||
#endif
|
|
||||||
.onEnter = NULL,
|
|
||||||
.onExit = NULL,
|
|
||||||
.onGlobalExit = NULL,
|
|
||||||
.entries = saCmsMenuCommenceEntries,
|
|
||||||
};
|
|
||||||
|
|
||||||
#pragma GCC diagnostic push
|
|
||||||
#if (__GNUC__ > 7)
|
|
||||||
// This is safe on 32bit platforms, suppress warning for saCmsUserFreqGetString
|
|
||||||
#pragma GCC diagnostic ignored "-Wcast-function-type"
|
|
||||||
#endif
|
|
||||||
static const OSD_Entry saCmsMenuFreqModeEntries[] =
|
|
||||||
{
|
|
||||||
OSD_LABEL_ENTRY("- SMARTAUDIO -"),
|
|
||||||
|
|
||||||
OSD_LABEL_FUNC_DYN_ENTRY("", saCmsDrawStatusString),
|
|
||||||
{ "FREQ", {.menufunc = saCmsUserFreqGetString}, &saCmsMenuUserFreq, OME_Submenu, OPTSTRING },
|
|
||||||
OSD_TAB_CALLBACK_ENTRY("POWER", saCmsConfigPowerByGvar, &saCmsEntPower),
|
|
||||||
OSD_SUBMENU_ENTRY("SET", &saCmsMenuCommence),
|
|
||||||
OSD_SUBMENU_ENTRY("CONFIG", &saCmsMenuConfig),
|
|
||||||
|
|
||||||
OSD_BACK_AND_END_ENTRY,
|
|
||||||
};
|
|
||||||
#pragma GCC diagnostic pop
|
|
||||||
|
|
||||||
static const OSD_Entry saCmsMenuChanModeEntries[] =
|
|
||||||
{
|
|
||||||
OSD_LABEL_ENTRY("- SMARTAUDIO -"),
|
|
||||||
|
|
||||||
OSD_LABEL_FUNC_DYN_ENTRY("", saCmsDrawStatusString),
|
|
||||||
OSD_TAB_CALLBACK_ENTRY("BAND", saCmsConfigBandByGvar, &saCmsEntBand),
|
|
||||||
OSD_TAB_CALLBACK_ENTRY("CHAN", saCmsConfigChanByGvar, &saCmsEntChan),
|
|
||||||
OSD_UINT16_RO_ENTRY("(FREQ)", &saCmsFreqRef),
|
|
||||||
OSD_TAB_CALLBACK_ENTRY("POWER", saCmsConfigPowerByGvar, &saCmsEntPower),
|
|
||||||
OSD_SUBMENU_ENTRY("SET", &saCmsMenuCommence),
|
|
||||||
OSD_SUBMENU_ENTRY("CONFIG", &saCmsMenuConfig),
|
|
||||||
|
|
||||||
OSD_BACK_AND_END_ENTRY,
|
|
||||||
};
|
|
||||||
|
|
||||||
static const OSD_Entry saCmsMenuOfflineEntries[] =
|
|
||||||
{
|
|
||||||
OSD_LABEL_ENTRY("- VTX SMARTAUDIO -"),
|
|
||||||
|
|
||||||
OSD_LABEL_FUNC_DYN_ENTRY("", saCmsDrawStatusString),
|
|
||||||
#ifdef USE_EXTENDED_CMS_MENUS
|
|
||||||
OSD_SUBMENU_ENTRY("STATX", &saCmsMenuStats),
|
|
||||||
#endif /* USE_EXTENDED_CMS_MENUS */
|
|
||||||
|
|
||||||
OSD_BACK_AND_END_ENTRY,
|
|
||||||
};
|
|
||||||
|
|
||||||
CMS_Menu cmsx_menuVtxSmartAudio; // Forward
|
|
||||||
|
|
||||||
static long sacms_SetupTopMenu(const OSD_Entry *from)
|
|
||||||
{
|
|
||||||
UNUSED(from);
|
|
||||||
|
|
||||||
if (saCmsDeviceStatus) {
|
|
||||||
if (saCmsFselModeNew == 0)
|
|
||||||
cmsx_menuVtxSmartAudio.entries = saCmsMenuChanModeEntries;
|
|
||||||
else
|
|
||||||
cmsx_menuVtxSmartAudio.entries = saCmsMenuFreqModeEntries;
|
|
||||||
} else {
|
|
||||||
cmsx_menuVtxSmartAudio.entries = saCmsMenuOfflineEntries;
|
|
||||||
}
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
CMS_Menu cmsx_menuVtxSmartAudio = {
|
|
||||||
#ifdef CMS_MENU_DEBUG
|
|
||||||
.GUARD_text = "XVTXSA",
|
|
||||||
.GUARD_type = OME_MENU,
|
|
||||||
#endif
|
|
||||||
.onEnter = sacms_SetupTopMenu,
|
|
||||||
.onExit = NULL,
|
|
||||||
.onGlobalExit = NULL,
|
|
||||||
.entries = saCmsMenuOfflineEntries,
|
|
||||||
};
|
|
||||||
|
|
||||||
#endif // CMS
|
|
|
@ -1,29 +0,0 @@
|
||||||
/*
|
|
||||||
* This file is part of Cleanflight and Betaflight.
|
|
||||||
*
|
|
||||||
* Cleanflight and Betaflight are free software. You can redistribute
|
|
||||||
* this software and/or modify this software under the terms of the
|
|
||||||
* GNU General Public License as published by the Free Software
|
|
||||||
* Foundation, either version 3 of the License, or (at your option)
|
|
||||||
* any later version.
|
|
||||||
*
|
|
||||||
* Cleanflight and Betaflight are distributed in the hope that they
|
|
||||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
|
||||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
|
||||||
* See the GNU General Public License for more details.
|
|
||||||
*
|
|
||||||
* You should have received a copy of the GNU General Public License
|
|
||||||
* along with this software.
|
|
||||||
*
|
|
||||||
* If not, see <http://www.gnu.org/licenses/>.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#pragma once
|
|
||||||
|
|
||||||
#include "cms/cms.h"
|
|
||||||
#include "cms/cms_types.h"
|
|
||||||
|
|
||||||
extern CMS_Menu cmsx_menuVtxSmartAudio;
|
|
||||||
|
|
||||||
void saCmsUpdate(void);
|
|
||||||
void saCmsResetOpmodel(void);
|
|
|
@ -1,254 +0,0 @@
|
||||||
/*
|
|
||||||
* This file is part of Cleanflight and Betaflight.
|
|
||||||
*
|
|
||||||
* Cleanflight and Betaflight are free software. You can redistribute
|
|
||||||
* this software and/or modify this software under the terms of the
|
|
||||||
* GNU General Public License as published by the Free Software
|
|
||||||
* Foundation, either version 3 of the License, or (at your option)
|
|
||||||
* any later version.
|
|
||||||
*
|
|
||||||
* Cleanflight and Betaflight are distributed in the hope that they
|
|
||||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
|
||||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
|
||||||
* See the GNU General Public License for more details.
|
|
||||||
*
|
|
||||||
* You should have received a copy of the GNU General Public License
|
|
||||||
* along with this software.
|
|
||||||
*
|
|
||||||
* If not, see <http://www.gnu.org/licenses/>.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <ctype.h>
|
|
||||||
#include <stdbool.h>
|
|
||||||
#include <stdint.h>
|
|
||||||
#include <string.h>
|
|
||||||
|
|
||||||
#include "platform.h"
|
|
||||||
|
|
||||||
#if defined(USE_CMS) && defined(USE_VTX_TRAMP)
|
|
||||||
|
|
||||||
#include "common/printf.h"
|
|
||||||
#include "common/utils.h"
|
|
||||||
|
|
||||||
#include "cms/cms.h"
|
|
||||||
#include "cms/cms_types.h"
|
|
||||||
|
|
||||||
#include "drivers/vtx_common.h"
|
|
||||||
|
|
||||||
#include "fc/config.h"
|
|
||||||
|
|
||||||
#include "io/vtx_string.h"
|
|
||||||
#include "io/vtx_tramp.h"
|
|
||||||
#include "io/vtx.h"
|
|
||||||
|
|
||||||
static bool trampCmsDrawStatusString(char *buf, unsigned bufsize)
|
|
||||||
{
|
|
||||||
const char *defaultString = "- -- ---- ----";
|
|
||||||
// m bc ffff tppp
|
|
||||||
// 01234567890123
|
|
||||||
|
|
||||||
if (bufsize < strlen(defaultString) + 1) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
strcpy(buf, defaultString);
|
|
||||||
|
|
||||||
vtxDevice_t *vtxDevice = vtxCommonDevice();
|
|
||||||
if (!vtxDevice || vtxCommonGetDeviceType(vtxDevice) != VTXDEV_TRAMP || !vtxCommonDeviceIsReady(vtxDevice)) {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
buf[0] = '*';
|
|
||||||
buf[1] = ' ';
|
|
||||||
buf[2] = vtx58BandLetter[trampData.band];
|
|
||||||
buf[3] = vtx58ChannelNames[trampData.channel][0];
|
|
||||||
buf[4] = ' ';
|
|
||||||
|
|
||||||
if (trampData.curFreq)
|
|
||||||
tfp_sprintf(&buf[5], "%4d", trampData.curFreq);
|
|
||||||
else
|
|
||||||
tfp_sprintf(&buf[5], "----");
|
|
||||||
|
|
||||||
if (trampData.power) {
|
|
||||||
tfp_sprintf(&buf[9], " %c%3d", (trampData.power == trampData.configuredPower) ? ' ' : '*', trampData.power);
|
|
||||||
} else {
|
|
||||||
tfp_sprintf(&buf[9], " ----");
|
|
||||||
}
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t trampCmsPitMode = 0;
|
|
||||||
uint8_t trampCmsBand = 1;
|
|
||||||
uint8_t trampCmsChan = 1;
|
|
||||||
uint16_t trampCmsFreqRef;
|
|
||||||
|
|
||||||
static const OSD_TAB_t trampCmsEntBand = { &trampCmsBand, VTX_TRAMP_BAND_COUNT, vtx58BandNames };
|
|
||||||
|
|
||||||
static const OSD_TAB_t trampCmsEntChan = { &trampCmsChan, VTX_TRAMP_CHANNEL_COUNT, vtx58ChannelNames };
|
|
||||||
|
|
||||||
static uint8_t trampCmsPower = 1;
|
|
||||||
|
|
||||||
static const OSD_TAB_t trampCmsEntPower = { &trampCmsPower, VTX_TRAMP_POWER_COUNT, trampPowerNames };
|
|
||||||
|
|
||||||
static void trampCmsUpdateFreqRef(void)
|
|
||||||
{
|
|
||||||
if (trampCmsBand > 0 && trampCmsChan > 0)
|
|
||||||
trampCmsFreqRef = vtx58frequencyTable[trampCmsBand - 1][trampCmsChan - 1];
|
|
||||||
}
|
|
||||||
|
|
||||||
static long trampCmsConfigBand(displayPort_t *pDisp, const void *self)
|
|
||||||
{
|
|
||||||
UNUSED(pDisp);
|
|
||||||
UNUSED(self);
|
|
||||||
|
|
||||||
if (trampCmsBand == 0)
|
|
||||||
// Bounce back
|
|
||||||
trampCmsBand = 1;
|
|
||||||
else
|
|
||||||
trampCmsUpdateFreqRef();
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static long trampCmsConfigChan(displayPort_t *pDisp, const void *self)
|
|
||||||
{
|
|
||||||
UNUSED(pDisp);
|
|
||||||
UNUSED(self);
|
|
||||||
|
|
||||||
if (trampCmsChan == 0)
|
|
||||||
// Bounce back
|
|
||||||
trampCmsChan = 1;
|
|
||||||
else
|
|
||||||
trampCmsUpdateFreqRef();
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static long trampCmsConfigPower(displayPort_t *pDisp, const void *self)
|
|
||||||
{
|
|
||||||
UNUSED(pDisp);
|
|
||||||
UNUSED(self);
|
|
||||||
|
|
||||||
if (trampCmsPower == 0)
|
|
||||||
// Bounce back
|
|
||||||
trampCmsPower = 1;
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static const char * const trampCmsPitModeNames[] = {
|
|
||||||
"---", "OFF", "ON "
|
|
||||||
};
|
|
||||||
|
|
||||||
static const 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;
|
|
||||||
} else {
|
|
||||||
trampSetPitMode(trampCmsPitMode - 1);
|
|
||||||
}
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static long trampCmsCommence(displayPort_t *pDisp, const void *self)
|
|
||||||
{
|
|
||||||
UNUSED(pDisp);
|
|
||||||
UNUSED(self);
|
|
||||||
|
|
||||||
trampSetBandAndChannel(trampCmsBand, trampCmsChan);
|
|
||||||
trampSetRFPower(trampPowerTable[trampCmsPower-1]);
|
|
||||||
|
|
||||||
// If it fails, the user should retry later
|
|
||||||
trampCommitChanges();
|
|
||||||
|
|
||||||
// update'vtx_' settings
|
|
||||||
vtxSettingsConfigMutable()->band = trampCmsBand;
|
|
||||||
vtxSettingsConfigMutable()->channel = trampCmsChan;
|
|
||||||
vtxSettingsConfigMutable()->power = trampCmsPower;
|
|
||||||
vtxSettingsConfigMutable()->freq = vtx58_Bandchan2Freq(trampCmsBand, trampCmsChan);
|
|
||||||
|
|
||||||
saveConfigAndNotify();
|
|
||||||
|
|
||||||
return MENU_CHAIN_BACK;
|
|
||||||
}
|
|
||||||
|
|
||||||
static void trampCmsInitSettings(void)
|
|
||||||
{
|
|
||||||
if (trampData.band > 0) trampCmsBand = trampData.band;
|
|
||||||
if (trampData.channel > 0) trampCmsChan = trampData.channel;
|
|
||||||
|
|
||||||
trampCmsUpdateFreqRef();
|
|
||||||
trampCmsPitMode = trampData.pitMode + 1;
|
|
||||||
|
|
||||||
if (trampData.configuredPower > 0) {
|
|
||||||
for (uint8_t i = 0; i < VTX_TRAMP_POWER_COUNT; i++) {
|
|
||||||
if (trampData.configuredPower <= trampPowerTable[i]) {
|
|
||||||
trampCmsPower = i + 1;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static long trampCmsOnEnter(const OSD_Entry *from)
|
|
||||||
{
|
|
||||||
UNUSED(from);
|
|
||||||
|
|
||||||
trampCmsInitSettings();
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static const OSD_Entry trampCmsMenuCommenceEntries[] =
|
|
||||||
{
|
|
||||||
OSD_LABEL_ENTRY("CONFIRM"),
|
|
||||||
OSD_FUNC_CALL_ENTRY("YES", trampCmsCommence),
|
|
||||||
|
|
||||||
OSD_BACK_AND_END_ENTRY,
|
|
||||||
};
|
|
||||||
|
|
||||||
static const CMS_Menu trampCmsMenuCommence = {
|
|
||||||
#ifdef CMS_MENU_DEBUG
|
|
||||||
.GUARD_text = "XVTXTRC",
|
|
||||||
.GUARD_type = OME_MENU,
|
|
||||||
#endif
|
|
||||||
.onEnter = NULL,
|
|
||||||
.onExit = NULL,
|
|
||||||
.onGlobalExit = NULL,
|
|
||||||
.entries = trampCmsMenuCommenceEntries,
|
|
||||||
};
|
|
||||||
|
|
||||||
static const OSD_Entry trampMenuEntries[] =
|
|
||||||
{
|
|
||||||
OSD_LABEL_ENTRY("- TRAMP -"),
|
|
||||||
|
|
||||||
OSD_LABEL_FUNC_DYN_ENTRY("", trampCmsDrawStatusString),
|
|
||||||
OSD_TAB_CALLBACK_ENTRY("PIT", trampCmsSetPitMode, &trampCmsEntPitMode),
|
|
||||||
OSD_TAB_CALLBACK_ENTRY("BAND", trampCmsConfigBand, &trampCmsEntBand),
|
|
||||||
OSD_TAB_CALLBACK_ENTRY("CHAN", trampCmsConfigChan, &trampCmsEntChan),
|
|
||||||
OSD_UINT16_RO_ENTRY("(FREQ)", &trampCmsFreqRef),
|
|
||||||
OSD_TAB_CALLBACK_ENTRY("POWER", trampCmsConfigPower, &trampCmsEntPower),
|
|
||||||
OSD_INT16_RO_ENTRY("T(C)", &trampData.temperature),
|
|
||||||
OSD_SUBMENU_ENTRY("SET", &trampCmsMenuCommence),
|
|
||||||
|
|
||||||
OSD_BACK_AND_END_ENTRY,
|
|
||||||
};
|
|
||||||
|
|
||||||
const CMS_Menu cmsx_menuVtxTramp = {
|
|
||||||
#ifdef CMS_MENU_DEBUG
|
|
||||||
.GUARD_text = "XVTXTR",
|
|
||||||
.GUARD_type = OME_MENU,
|
|
||||||
#endif
|
|
||||||
.onEnter = trampCmsOnEnter,
|
|
||||||
.onExit = NULL,
|
|
||||||
.onGlobalExit = NULL,
|
|
||||||
.entries = trampMenuEntries,
|
|
||||||
};
|
|
||||||
#endif
|
|
|
@ -1,23 +0,0 @@
|
||||||
/*
|
|
||||||
* 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 "cms/cms.h"
|
|
||||||
#include "cms/cms_types.h"
|
|
||||||
|
|
||||||
extern const CMS_Menu cmsx_menuVtxTramp;
|
|
|
@ -103,13 +103,6 @@ void vtxCommonSetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void vtxCommonSetFrequency(vtxDevice_t *vtxDevice, uint16_t frequency)
|
|
||||||
{
|
|
||||||
if (vtxDevice && vtxDevice->vTable->setFrequency) {
|
|
||||||
vtxDevice->vTable->setFrequency(vtxDevice, frequency);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
bool vtxCommonGetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t *pBand, uint8_t *pChannel)
|
bool vtxCommonGetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t *pBand, uint8_t *pChannel)
|
||||||
{
|
{
|
||||||
if (vtxDevice && vtxDevice->vTable->getBandAndChannel) {
|
if (vtxDevice && vtxDevice->vTable->getBandAndChannel) {
|
||||||
|
@ -150,3 +143,35 @@ bool vtxCommonGetDeviceCapability(vtxDevice_t *vtxDevice, vtxDeviceCapability_t
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool vtxCommonGetPower(const vtxDevice_t *vtxDevice, uint8_t *pIndex, uint16_t *pPowerMw)
|
||||||
|
{
|
||||||
|
if (vtxDevice && vtxDevice->vTable->getPower) {
|
||||||
|
return vtxDevice->vTable->getPower(vtxDevice, pIndex, pPowerMw);
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool vtxCommonGetOsdInfo(vtxDevice_t *vtxDevice, vtxDeviceOsdInfo_t * pOsdInfo)
|
||||||
|
{
|
||||||
|
bool ret = false;
|
||||||
|
|
||||||
|
if (vtxDevice && vtxDevice->vTable->getOsdInfo) {
|
||||||
|
ret = vtxDevice->vTable->getOsdInfo(vtxDevice, pOsdInfo);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Make sure we provide sane results even in case API fails
|
||||||
|
if (!ret) {
|
||||||
|
pOsdInfo->band = 0;
|
||||||
|
pOsdInfo->channel = 0;
|
||||||
|
pOsdInfo->frequency = 0;
|
||||||
|
pOsdInfo->powerIndex = 0;
|
||||||
|
pOsdInfo->powerMilliwatt = 0;
|
||||||
|
pOsdInfo->bandLetter = '-';
|
||||||
|
pOsdInfo->bandName = "-";
|
||||||
|
pOsdInfo->channelName = "-";
|
||||||
|
pOsdInfo->powerIndexLetter = '0';
|
||||||
|
}
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
|
@ -30,19 +30,12 @@
|
||||||
|
|
||||||
#define VTX_SETTINGS_DEFAULT_BAND 4
|
#define VTX_SETTINGS_DEFAULT_BAND 4
|
||||||
#define VTX_SETTINGS_DEFAULT_CHANNEL 1
|
#define VTX_SETTINGS_DEFAULT_CHANNEL 1
|
||||||
#define VTX_SETTINGS_DEFAULT_FREQ 5740
|
#define VTX_SETTINGS_DEFAULT_PITMODE_CHANNEL 1
|
||||||
#define VTX_SETTINGS_DEFAULT_PITMODE_FREQ 0
|
|
||||||
#define VTX_SETTINGS_DEFAULT_LOW_POWER_DISARM 0
|
#define VTX_SETTINGS_DEFAULT_LOW_POWER_DISARM 0
|
||||||
|
|
||||||
#define VTX_SETTINGS_MIN_FREQUENCY_MHZ 0 //min freq (in MHz) for 'vtx_freq' setting
|
#define VTX_SETTINGS_MIN_FREQUENCY_MHZ 0 //min freq (in MHz) for 'vtx_freq' setting
|
||||||
#define VTX_SETTINGS_MAX_FREQUENCY_MHZ 5999 //max freq (in MHz) for 'vtx_freq' setting
|
#define VTX_SETTINGS_MAX_FREQUENCY_MHZ 5999 //max freq (in MHz) for 'vtx_freq' setting
|
||||||
|
|
||||||
#if defined(USE_VTX_RTC6705)
|
|
||||||
|
|
||||||
#include "drivers/vtx_rtc6705.h"
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP)
|
#if defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP)
|
||||||
|
|
||||||
#define VTX_SETTINGS_POWER_COUNT 5
|
#define VTX_SETTINGS_POWER_COUNT 5
|
||||||
|
@ -53,13 +46,6 @@
|
||||||
#define VTX_SETTINGS_FREQCMD
|
#define VTX_SETTINGS_FREQCMD
|
||||||
#define VTX_SETTINGS_MAX_POWER (VTX_SETTINGS_POWER_COUNT - VTX_SETTINGS_MIN_POWER + 1)
|
#define VTX_SETTINGS_MAX_POWER (VTX_SETTINGS_POWER_COUNT - VTX_SETTINGS_MIN_POWER + 1)
|
||||||
|
|
||||||
#elif defined(USE_VTX_RTC6705)
|
|
||||||
|
|
||||||
#define VTX_SETTINGS_POWER_COUNT VTX_RTC6705_POWER_COUNT
|
|
||||||
#define VTX_SETTINGS_DEFAULT_POWER VTX_RTC6705_DEFAULT_POWER
|
|
||||||
#define VTX_SETTINGS_MIN_POWER VTX_RTC6705_MIN_POWER
|
|
||||||
#define VTX_SETTINGS_MAX_POWER (VTX_SETTINGS_POWER_COUNT - 1)
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// check value for MSP_SET_VTX_CONFIG to determine if value is encoded
|
// check value for MSP_SET_VTX_CONFIG to determine if value is encoded
|
||||||
|
@ -68,7 +54,7 @@
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
VTXDEV_UNSUPPORTED = 0, // reserved for MSP
|
VTXDEV_UNSUPPORTED = 0, // reserved for MSP
|
||||||
VTXDEV_RTC6705 = 1,
|
VTXDEV_RTC6705 = 1, // deprecated
|
||||||
// 2 reserved
|
// 2 reserved
|
||||||
VTXDEV_SMARTAUDIO = 3,
|
VTXDEV_SMARTAUDIO = 3,
|
||||||
VTXDEV_TRAMP = 4,
|
VTXDEV_TRAMP = 4,
|
||||||
|
@ -82,23 +68,32 @@ typedef struct vtxDeviceCapability_s {
|
||||||
uint8_t bandCount;
|
uint8_t bandCount;
|
||||||
uint8_t channelCount;
|
uint8_t channelCount;
|
||||||
uint8_t powerCount;
|
uint8_t powerCount;
|
||||||
|
char **bandNames;
|
||||||
|
char **channelNames;
|
||||||
|
char **powerNames;
|
||||||
} vtxDeviceCapability_t;
|
} vtxDeviceCapability_t;
|
||||||
|
|
||||||
|
typedef struct vtxDeviceOsdInfo_s {
|
||||||
|
int band;
|
||||||
|
int channel;
|
||||||
|
int frequency;
|
||||||
|
int powerIndex;
|
||||||
|
int powerMilliwatt;
|
||||||
|
char bandLetter;
|
||||||
|
const char * bandName;
|
||||||
|
const char * channelName;
|
||||||
|
char powerIndexLetter;
|
||||||
|
} vtxDeviceOsdInfo_t;
|
||||||
|
|
||||||
typedef struct vtxDevice_s {
|
typedef struct vtxDevice_s {
|
||||||
const struct vtxVTable_s * const vTable;
|
const struct vtxVTable_s * const vTable;
|
||||||
|
|
||||||
vtxDeviceCapability_t capability;
|
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 band; // Band = 1, 1-based
|
||||||
uint8_t channel; // CH1 = 1, 1-based
|
uint8_t channel; // CH1 = 1, 1-based
|
||||||
uint8_t powerIndex; // Lowest/Off = 0
|
uint8_t powerIndex; // Lowest/Off = 0
|
||||||
uint8_t pitMode; // 0 = non-PIT, 1 = PIT
|
uint8_t pitMode; // 0 = non-PIT, 1 = PIT
|
||||||
|
|
||||||
} vtxDevice_t;
|
} vtxDevice_t;
|
||||||
|
|
||||||
// {set,get}BandAndChannel: band and channel are 1 origin
|
// {set,get}BandAndChannel: band and channel are 1 origin
|
||||||
|
@ -113,12 +108,14 @@ typedef struct vtxVTable_s {
|
||||||
void (*setBandAndChannel)(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channel);
|
void (*setBandAndChannel)(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channel);
|
||||||
void (*setPowerByIndex)(vtxDevice_t *vtxDevice, uint8_t level);
|
void (*setPowerByIndex)(vtxDevice_t *vtxDevice, uint8_t level);
|
||||||
void (*setPitMode)(vtxDevice_t *vtxDevice, uint8_t onoff);
|
void (*setPitMode)(vtxDevice_t *vtxDevice, uint8_t onoff);
|
||||||
void (*setFrequency)(vtxDevice_t *vtxDevice, uint16_t freq);
|
|
||||||
|
|
||||||
bool (*getBandAndChannel)(const vtxDevice_t *vtxDevice, uint8_t *pBand, uint8_t *pChannel);
|
bool (*getBandAndChannel)(const vtxDevice_t *vtxDevice, uint8_t *pBand, uint8_t *pChannel);
|
||||||
bool (*getPowerIndex)(const vtxDevice_t *vtxDevice, uint8_t *pIndex);
|
bool (*getPowerIndex)(const vtxDevice_t *vtxDevice, uint8_t *pIndex);
|
||||||
bool (*getPitMode)(const vtxDevice_t *vtxDevice, uint8_t *pOnOff);
|
bool (*getPitMode)(const vtxDevice_t *vtxDevice, uint8_t *pOnOff);
|
||||||
bool (*getFrequency)(const vtxDevice_t *vtxDevice, uint16_t *pFreq);
|
bool (*getFrequency)(const vtxDevice_t *vtxDevice, uint16_t *pFreq);
|
||||||
|
|
||||||
|
bool (*getPower)(const vtxDevice_t *vtxDevice, uint8_t *pIndex, uint16_t *pPowerMw);
|
||||||
|
bool (*getOsdInfo)(const vtxDevice_t *vtxDevice, vtxDeviceOsdInfo_t * pOsdInfo);
|
||||||
} vtxVTable_t;
|
} vtxVTable_t;
|
||||||
|
|
||||||
// 3.1.0
|
// 3.1.0
|
||||||
|
@ -137,9 +134,10 @@ bool vtxCommonDeviceIsReady(vtxDevice_t *vtxDevice);
|
||||||
void vtxCommonSetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channel);
|
void vtxCommonSetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channel);
|
||||||
void vtxCommonSetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index);
|
void vtxCommonSetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index);
|
||||||
void vtxCommonSetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff);
|
void vtxCommonSetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff);
|
||||||
void vtxCommonSetFrequency(vtxDevice_t *vtxDevice, uint16_t frequency);
|
|
||||||
bool vtxCommonGetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t *pBand, uint8_t *pChannel);
|
bool vtxCommonGetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t *pBand, uint8_t *pChannel);
|
||||||
bool vtxCommonGetPowerIndex(vtxDevice_t *vtxDevice, uint8_t *pIndex);
|
bool vtxCommonGetPowerIndex(vtxDevice_t *vtxDevice, uint8_t *pIndex);
|
||||||
bool vtxCommonGetPitMode(vtxDevice_t *vtxDevice, uint8_t *pOnOff);
|
bool vtxCommonGetPitMode(vtxDevice_t *vtxDevice, uint8_t *pOnOff);
|
||||||
bool vtxCommonGetFrequency(const vtxDevice_t *vtxDevice, uint16_t *pFreq);
|
bool vtxCommonGetFrequency(const vtxDevice_t *vtxDevice, uint16_t *pFreq);
|
||||||
bool vtxCommonGetDeviceCapability(vtxDevice_t *vtxDevice, vtxDeviceCapability_t *pDeviceCapability);
|
bool vtxCommonGetDeviceCapability(vtxDevice_t *vtxDevice, vtxDeviceCapability_t *pDeviceCapability);
|
||||||
|
bool vtxCommonGetPower(const vtxDevice_t *vtxDevice, uint8_t *pIndex, uint16_t *pPowerMw);
|
||||||
|
bool vtxCommonGetOsdInfo(vtxDevice_t *vtxDevice, vtxDeviceOsdInfo_t * pOsdInfo);
|
||||||
|
|
|
@ -1,264 +0,0 @@
|
||||||
/*
|
|
||||||
* 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/>.
|
|
||||||
*/
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Author: Giles Burgess (giles@multiflite.co.uk)
|
|
||||||
*
|
|
||||||
* This source code is provided as is and can be used/modified so long
|
|
||||||
* as this header is maintained with the file at all times.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <stdbool.h>
|
|
||||||
#include <stdint.h>
|
|
||||||
|
|
||||||
#include "platform.h"
|
|
||||||
|
|
||||||
#if defined(USE_VTX_RTC6705) && !defined(VTX_RTC6705SOFTSPI)
|
|
||||||
|
|
||||||
#include "common/maths.h"
|
|
||||||
|
|
||||||
#include "drivers/bus_spi.h"
|
|
||||||
#include "drivers/io.h"
|
|
||||||
#include "drivers/system.h"
|
|
||||||
#include "drivers/time.h"
|
|
||||||
|
|
||||||
#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
|
|
||||||
#define RTC6705_SET_A3 0x8E3331 //5825
|
|
||||||
#define RTC6705_SET_A4 0x8DB4B1 //5805
|
|
||||||
#define RTC6705_SET_A5 0x8D3631 //5785
|
|
||||||
#define RTC6705_SET_A6 0x8CB7B1 //5765
|
|
||||||
#define RTC6705_SET_A7 0x8C4131 //5745
|
|
||||||
#define RTC6705_SET_A8 0x8BC2B1 //5725
|
|
||||||
#define RTC6705_SET_B1 0x8BF3B1 //5733
|
|
||||||
#define RTC6705_SET_B2 0x8C6711 //5752
|
|
||||||
#define RTC6705_SET_B3 0x8CE271 //5771
|
|
||||||
#define RTC6705_SET_B4 0x8D55D1 //5790
|
|
||||||
#define RTC6705_SET_B5 0x8DD131 //5809
|
|
||||||
#define RTC6705_SET_B6 0x8E4491 //5828
|
|
||||||
#define RTC6705_SET_B7 0x8EB7F1 //5847
|
|
||||||
#define RTC6705_SET_B8 0x8F3351 //5866
|
|
||||||
#define RTC6705_SET_E1 0x8B4431 //5705
|
|
||||||
#define RTC6705_SET_E2 0x8AC5B1 //5685
|
|
||||||
#define RTC6705_SET_E3 0x8A4731 //5665
|
|
||||||
#define RTC6705_SET_E4 0x89D0B1 //5645
|
|
||||||
#define RTC6705_SET_E5 0x8FA6B1 //5885
|
|
||||||
#define RTC6705_SET_E6 0x902531 //5905
|
|
||||||
#define RTC6705_SET_E7 0x90A3B1 //5925
|
|
||||||
#define RTC6705_SET_E8 0x912231 //5945
|
|
||||||
#define RTC6705_SET_F1 0x8C2191 //5740
|
|
||||||
#define RTC6705_SET_F2 0x8CA011 //5760
|
|
||||||
#define RTC6705_SET_F3 0x8D1691 //5780
|
|
||||||
#define RTC6705_SET_F4 0x8D9511 //5800
|
|
||||||
#define RTC6705_SET_F5 0x8E1391 //5820
|
|
||||||
#define RTC6705_SET_F6 0x8E9211 //5840
|
|
||||||
#define RTC6705_SET_F7 0x8F1091 //5860
|
|
||||||
#define RTC6705_SET_F8 0x8F8711 //5880
|
|
||||||
#define RTC6705_SET_R1 0x8A2151 //5658
|
|
||||||
#define RTC6705_SET_R2 0x8B04F1 //5695
|
|
||||||
#define RTC6705_SET_R3 0x8BF091 //5732
|
|
||||||
#define RTC6705_SET_R4 0x8CD431 //5769
|
|
||||||
#define RTC6705_SET_R5 0x8DB7D1 //5806
|
|
||||||
#define RTC6705_SET_R6 0x8EA371 //5843
|
|
||||||
#define RTC6705_SET_R7 0x8F8711 //5880
|
|
||||||
#define RTC6705_SET_R8 0x9072B1 //5917
|
|
||||||
|
|
||||||
#define RTC6705_SET_R 400 //Reference clock
|
|
||||||
#define RTC6705_SET_FDIV 1024 //128*(fosc/1000000)
|
|
||||||
#define RTC6705_SET_NDIV 16 //Remainder divider to get 'A' part of equation
|
|
||||||
#define RTC6705_SET_WRITE 0x11 //10001b to write to register
|
|
||||||
#define RTC6705_SET_DIVMULT 1000000 //Division value (to fit into a uint32_t) (Hz to MHz)
|
|
||||||
|
|
||||||
#ifdef RTC6705_POWER_PIN
|
|
||||||
static IO_t vtxPowerPin = IO_NONE;
|
|
||||||
#endif
|
|
||||||
static IO_t vtxCSPin = IO_NONE;
|
|
||||||
|
|
||||||
#define DISABLE_RTC6705() IOHi(vtxCSPin)
|
|
||||||
|
|
||||||
#ifdef USE_RTC6705_CLK_HACK
|
|
||||||
static IO_t vtxCLKPin = IO_NONE;
|
|
||||||
// HACK for missing pull up on CLK line - drive the CLK high *before* enabling the CS pin.
|
|
||||||
#define ENABLE_RTC6705() {IOHi(vtxCLKPin); delayMicroseconds(5); IOLo(vtxCSPin); }
|
|
||||||
#else
|
|
||||||
#define ENABLE_RTC6705() IOLo(vtxCSPin)
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define DP_5G_MASK 0x7000 // b111000000000000
|
|
||||||
#define PA5G_BS_MASK 0x0E00 // b000111000000000
|
|
||||||
#define PA5G_PW_MASK 0x0180 // b000000110000000
|
|
||||||
#define PD_Q5G_MASK 0x0040 // b000000001000000
|
|
||||||
#define QI_5G_MASK 0x0038 // b000000000111000
|
|
||||||
#define PA_BS_MASK 0x0007 // b000000000000111
|
|
||||||
|
|
||||||
#define PA_CONTROL_DEFAULT 0x4FBD
|
|
||||||
|
|
||||||
#define RTC6705_RW_CONTROL_BIT (1 << 4)
|
|
||||||
#define RTC6705_ADDRESS (0x07)
|
|
||||||
|
|
||||||
#define ENABLE_VTX_POWER() IOLo(vtxPowerPin)
|
|
||||||
#define DISABLE_VTX_POWER() IOHi(vtxPowerPin)
|
|
||||||
|
|
||||||
|
|
||||||
// Define variables
|
|
||||||
static const uint32_t channelArray[VTX_RTC6705_BAND_COUNT][VTX_RTC6705_CHANNEL_COUNT] = {
|
|
||||||
{ RTC6705_SET_A1, RTC6705_SET_A2, RTC6705_SET_A3, RTC6705_SET_A4, RTC6705_SET_A5, RTC6705_SET_A6, RTC6705_SET_A7, RTC6705_SET_A8 },
|
|
||||||
{ RTC6705_SET_B1, RTC6705_SET_B2, RTC6705_SET_B3, RTC6705_SET_B4, RTC6705_SET_B5, RTC6705_SET_B6, RTC6705_SET_B7, RTC6705_SET_B8 },
|
|
||||||
{ RTC6705_SET_E1, RTC6705_SET_E2, RTC6705_SET_E3, RTC6705_SET_E4, RTC6705_SET_E5, RTC6705_SET_E6, RTC6705_SET_E7, RTC6705_SET_E8 },
|
|
||||||
{ RTC6705_SET_F1, RTC6705_SET_F2, RTC6705_SET_F3, RTC6705_SET_F4, RTC6705_SET_F5, RTC6705_SET_F6, RTC6705_SET_F7, RTC6705_SET_F8 },
|
|
||||||
{ RTC6705_SET_R1, RTC6705_SET_R2, RTC6705_SET_R3, RTC6705_SET_R4, RTC6705_SET_R5, RTC6705_SET_R6, RTC6705_SET_R7, RTC6705_SET_R8 },
|
|
||||||
};
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Reverse a uint32_t (LSB to MSB)
|
|
||||||
* This is easier for when generating the frequency to then
|
|
||||||
* reverse the bits afterwards
|
|
||||||
*/
|
|
||||||
static uint32_t reverse32(uint32_t in)
|
|
||||||
{
|
|
||||||
uint32_t out = 0;
|
|
||||||
|
|
||||||
for (uint8_t i = 0 ; i < 32 ; i++)
|
|
||||||
{
|
|
||||||
out |= ((in>>i) & 1)<<(31-i);
|
|
||||||
}
|
|
||||||
|
|
||||||
return out;
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Start chip if available
|
|
||||||
*/
|
|
||||||
|
|
||||||
void rtc6705IOInit(void)
|
|
||||||
{
|
|
||||||
#ifdef RTC6705_POWER_PIN
|
|
||||||
|
|
||||||
vtxPowerPin = IOGetByTag(IO_TAG(RTC6705_POWER_PIN));
|
|
||||||
IOInit(vtxPowerPin, OWNER_VTX, RESOURCE_OUTPUT, 0);
|
|
||||||
|
|
||||||
DISABLE_VTX_POWER();
|
|
||||||
IOConfigGPIO(vtxPowerPin, IOCFG_OUT_PP);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_RTC6705_CLK_HACK
|
|
||||||
vtxCLKPin = IOGetByTag(IO_TAG(RTC6705_CLK_PIN));
|
|
||||||
// we assume the CLK pin will have been initialised by the SPI code.
|
|
||||||
#endif
|
|
||||||
|
|
||||||
vtxCSPin = IOGetByTag(IO_TAG(RTC6705_CS_PIN));
|
|
||||||
IOInit(vtxCSPin, OWNER_VTX, RESOURCE_OUTPUT, 0);
|
|
||||||
|
|
||||||
DISABLE_RTC6705();
|
|
||||||
// GPIO bit is enabled so here so the output is not pulled low when the GPIO is set in output mode.
|
|
||||||
// Note: It's critical to ensure that incorrect signals are not sent to the VTX.
|
|
||||||
IOConfigGPIO(vtxCSPin, IOCFG_OUT_PP);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Transfer a 25bit packet to RTC6705
|
|
||||||
* This will just send it as a 32bit packet LSB meaning
|
|
||||||
* extra 0's get truncated on RTC6705 end
|
|
||||||
*/
|
|
||||||
static void rtc6705Transfer(uint32_t command)
|
|
||||||
{
|
|
||||||
command = reverse32(command);
|
|
||||||
|
|
||||||
ENABLE_RTC6705();
|
|
||||||
|
|
||||||
spiTransferByte(RTC6705_SPI_INSTANCE, (command >> 24) & 0xFF);
|
|
||||||
spiTransferByte(RTC6705_SPI_INSTANCE, (command >> 16) & 0xFF);
|
|
||||||
spiTransferByte(RTC6705_SPI_INSTANCE, (command >> 8) & 0xFF);
|
|
||||||
spiTransferByte(RTC6705_SPI_INSTANCE, (command >> 0) & 0xFF);
|
|
||||||
|
|
||||||
delayMicroseconds(2);
|
|
||||||
|
|
||||||
DISABLE_RTC6705();
|
|
||||||
|
|
||||||
delayMicroseconds(2);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Set a band and channel
|
|
||||||
*/
|
|
||||||
void rtc6705SetBandAndChannel(uint8_t band, uint8_t channel)
|
|
||||||
{
|
|
||||||
band = constrain(band, 0, VTX_RTC6705_BAND_COUNT - 1);
|
|
||||||
channel = constrain(channel, 0, VTX_RTC6705_CHANNEL_COUNT - 1);
|
|
||||||
|
|
||||||
spiSetSpeed(RTC6705_SPI_INSTANCE, SPI_CLOCK_SLOW);
|
|
||||||
|
|
||||||
rtc6705Transfer(RTC6705_SET_HEAD);
|
|
||||||
rtc6705Transfer(channelArray[band][channel]);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Set a freq in mhz
|
|
||||||
* Formula derived from datasheet
|
|
||||||
*/
|
|
||||||
void rtc6705SetFreq(uint16_t frequency)
|
|
||||||
{
|
|
||||||
frequency = constrain(frequency, VTX_RTC6705_FREQ_MIN, VTX_RTC6705_FREQ_MAX);
|
|
||||||
|
|
||||||
uint32_t val_hex = 0;
|
|
||||||
|
|
||||||
uint32_t val_a = ((((uint64_t)frequency*(uint64_t)RTC6705_SET_DIVMULT*(uint64_t)RTC6705_SET_R)/(uint64_t)RTC6705_SET_DIVMULT) % RTC6705_SET_FDIV) / RTC6705_SET_NDIV; //Casts required to make sure correct math (large numbers)
|
|
||||||
uint32_t val_n = (((uint64_t)frequency*(uint64_t)RTC6705_SET_DIVMULT*(uint64_t)RTC6705_SET_R)/(uint64_t)RTC6705_SET_DIVMULT) / RTC6705_SET_FDIV; //Casts required to make sure correct math (large numbers)
|
|
||||||
|
|
||||||
val_hex |= RTC6705_SET_WRITE;
|
|
||||||
val_hex |= (val_a << 5);
|
|
||||||
val_hex |= (val_n << 12);
|
|
||||||
|
|
||||||
spiSetSpeed(RTC6705_SPI_INSTANCE, SPI_CLOCK_SLOW);
|
|
||||||
|
|
||||||
rtc6705Transfer(RTC6705_SET_HEAD);
|
|
||||||
delayMicroseconds(10);
|
|
||||||
rtc6705Transfer(val_hex);
|
|
||||||
}
|
|
||||||
|
|
||||||
void rtc6705SetRFPower(uint8_t rf_power)
|
|
||||||
{
|
|
||||||
rf_power = constrain(rf_power, 0, VTX_RTC6705_POWER_COUNT - 1);
|
|
||||||
|
|
||||||
spiSetSpeed(RTC6705_SPI_INSTANCE, SPI_CLOCK_SLOW);
|
|
||||||
|
|
||||||
uint32_t val_hex = RTC6705_RW_CONTROL_BIT; // write
|
|
||||||
val_hex |= RTC6705_ADDRESS; // address
|
|
||||||
uint32_t data = rf_power == 0 ? (PA_CONTROL_DEFAULT | PD_Q5G_MASK) & (~(PA5G_PW_MASK | PA5G_BS_MASK)) : PA_CONTROL_DEFAULT;
|
|
||||||
val_hex |= data << 5; // 4 address bits and 1 rw bit.
|
|
||||||
|
|
||||||
rtc6705Transfer(val_hex);
|
|
||||||
}
|
|
||||||
|
|
||||||
void rtc6705Disable(void)
|
|
||||||
{
|
|
||||||
#ifdef RTC6705_POWER_PIN
|
|
||||||
DISABLE_VTX_POWER();
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
void rtc6705Enable(void)
|
|
||||||
{
|
|
||||||
#ifdef RTC6705_POWER_PIN
|
|
||||||
ENABLE_VTX_POWER();
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
|
@ -1,50 +0,0 @@
|
||||||
/*
|
|
||||||
* 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/>.
|
|
||||||
*/
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Author: Giles Burgess (giles@multiflite.co.uk)
|
|
||||||
*
|
|
||||||
* This source code is provided as is and can be used/modified so long
|
|
||||||
* as this header is maintained with the file at all times.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#pragma once
|
|
||||||
|
|
||||||
#include <stdint.h>
|
|
||||||
|
|
||||||
#define VTX_RTC6705_BAND_COUNT 5
|
|
||||||
#define VTX_RTC6705_CHANNEL_COUNT 8
|
|
||||||
#define VTX_RTC6705_POWER_COUNT 3
|
|
||||||
#define VTX_RTC6705_DEFAULT_POWER 1
|
|
||||||
|
|
||||||
#if defined(RTC6705_POWER_PIN)
|
|
||||||
#define VTX_RTC6705_MIN_POWER 0
|
|
||||||
#else
|
|
||||||
#define VTX_RTC6705_MIN_POWER 1
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define VTX_RTC6705_FREQ_MIN 5600
|
|
||||||
#define VTX_RTC6705_FREQ_MAX 5950
|
|
||||||
|
|
||||||
#define VTX_RTC6705_BOOT_DELAY 350 // milliseconds
|
|
||||||
|
|
||||||
void rtc6705IOInit(void);
|
|
||||||
void rtc6705SetBandAndChannel(const uint8_t band, const uint8_t channel);
|
|
||||||
void rtc6705SetFreq(const uint16_t freq);
|
|
||||||
void rtc6705SetRFPower(const uint8_t rf_power);
|
|
||||||
void rtc6705Disable(void);
|
|
||||||
void rtc6705Enable(void);
|
|
|
@ -1,156 +0,0 @@
|
||||||
/*
|
|
||||||
* 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 <stdbool.h>
|
|
||||||
#include <stdint.h>
|
|
||||||
|
|
||||||
#include "platform.h"
|
|
||||||
|
|
||||||
#if defined(USE_VTX_RTC6705) && defined(VTX_RTC6705SOFTSPI)
|
|
||||||
|
|
||||||
#include "drivers/bus_spi.h"
|
|
||||||
#include "drivers/io.h"
|
|
||||||
#include "drivers/system.h"
|
|
||||||
#include "light_led.h"
|
|
||||||
|
|
||||||
#include "vtx_rtc6705.h"
|
|
||||||
|
|
||||||
#define DP_5G_MASK 0x7000
|
|
||||||
#define PA5G_BS_MASK 0x0E00
|
|
||||||
#define PA5G_PW_MASK 0x0180
|
|
||||||
#define PD_Q5G_MASK 0x0040
|
|
||||||
#define QI_5G_MASK 0x0038
|
|
||||||
#define PA_BS_MASK 0x0007
|
|
||||||
|
|
||||||
#define PA_CONTROL_DEFAULT 0x4FBD
|
|
||||||
|
|
||||||
#define RTC6705_SPICLK_ON IOHi(rtc6705ClkPin)
|
|
||||||
#define RTC6705_SPICLK_OFF IOLo(rtc6705ClkPin)
|
|
||||||
|
|
||||||
#define RTC6705_SPIDATA_ON IOHi(rtc6705DataPin)
|
|
||||||
#define RTC6705_SPIDATA_OFF IOLo(rtc6705DataPin)
|
|
||||||
|
|
||||||
#define RTC6705_SPILE_ON IOHi(rtc6705LePin)
|
|
||||||
#define RTC6705_SPILE_OFF IOLo(rtc6705LePin)
|
|
||||||
|
|
||||||
const uint16_t vtx_freq[] =
|
|
||||||
{
|
|
||||||
5865, 5845, 5825, 5805, 5785, 5765, 5745, 5725, // Boacam A
|
|
||||||
5733, 5752, 5771, 5790, 5809, 5828, 5847, 5866, // Boscam B
|
|
||||||
5705, 5685, 5665, 5645, 5885, 5905, 5925, 5945, // Boscam E
|
|
||||||
5740, 5760, 5780, 5800, 5820, 5840, 5860, 5880, // FatShark
|
|
||||||
5658, 5695, 5732, 5769, 5806, 5843, 5880, 5917, // RaceBand
|
|
||||||
};
|
|
||||||
|
|
||||||
static IO_t rtc6705DataPin = IO_NONE;
|
|
||||||
static IO_t rtc6705LePin = IO_NONE;
|
|
||||||
static IO_t rtc6705ClkPin = IO_NONE;
|
|
||||||
|
|
||||||
void rtc6705IOInit(void)
|
|
||||||
{
|
|
||||||
rtc6705DataPin = IOGetByTag(IO_TAG(RTC6705_SPIDATA_PIN));
|
|
||||||
rtc6705LePin = IOGetByTag(IO_TAG(RTC6705_SPILE_PIN));
|
|
||||||
rtc6705ClkPin = IOGetByTag(IO_TAG(RTC6705_SPICLK_PIN));
|
|
||||||
|
|
||||||
IOInit(rtc6705DataPin, OWNER_SPI_MOSI, RESOURCE_SOFT_OFFSET);
|
|
||||||
IOConfigGPIO(rtc6705DataPin, IOCFG_OUT_PP);
|
|
||||||
|
|
||||||
IOInit(rtc6705LePin, OWNER_SPI_CS, RESOURCE_SOFT_OFFSET);
|
|
||||||
IOConfigGPIO(rtc6705LePin, IOCFG_OUT_PP);
|
|
||||||
|
|
||||||
IOInit(rtc6705ClkPin, OWNER_SPI_SCK, RESOURCE_SOFT_OFFSET);
|
|
||||||
IOConfigGPIO(rtc6705ClkPin, IOCFG_OUT_PP);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void rtc6705_write_register(uint8_t addr, uint32_t data)
|
|
||||||
{
|
|
||||||
uint8_t i;
|
|
||||||
|
|
||||||
RTC6705_SPILE_OFF;
|
|
||||||
delay(1);
|
|
||||||
// send address
|
|
||||||
for (i=0; i<4; i++) {
|
|
||||||
if ((addr >> i) & 1)
|
|
||||||
RTC6705_SPIDATA_ON;
|
|
||||||
else
|
|
||||||
RTC6705_SPIDATA_OFF;
|
|
||||||
|
|
||||||
RTC6705_SPICLK_ON;
|
|
||||||
delay(1);
|
|
||||||
RTC6705_SPICLK_OFF;
|
|
||||||
delay(1);
|
|
||||||
}
|
|
||||||
// Write bit
|
|
||||||
|
|
||||||
RTC6705_SPIDATA_ON;
|
|
||||||
RTC6705_SPICLK_ON;
|
|
||||||
delay(1);
|
|
||||||
RTC6705_SPICLK_OFF;
|
|
||||||
delay(1);
|
|
||||||
for (i=0; i<20; i++) {
|
|
||||||
if ((data >> i) & 1)
|
|
||||||
RTC6705_SPIDATA_ON;
|
|
||||||
else
|
|
||||||
RTC6705_SPIDATA_OFF;
|
|
||||||
RTC6705_SPICLK_ON;
|
|
||||||
delay(1);
|
|
||||||
RTC6705_SPICLK_OFF;
|
|
||||||
delay(1);
|
|
||||||
}
|
|
||||||
RTC6705_SPILE_ON;
|
|
||||||
}
|
|
||||||
|
|
||||||
void rtc6705SetFreq(uint16_t channel_freq)
|
|
||||||
{
|
|
||||||
uint32_t freq = (uint32_t)channel_freq * 1000;
|
|
||||||
uint32_t N, A;
|
|
||||||
|
|
||||||
freq /= 40;
|
|
||||||
N = freq / 64;
|
|
||||||
A = freq % 64;
|
|
||||||
rtc6705_write_register(0, 400);
|
|
||||||
rtc6705_write_register(1, (N << 7) | A);
|
|
||||||
}
|
|
||||||
|
|
||||||
void rtc6705SetBandAndChannel(const uint8_t band, const uint8_t channel)
|
|
||||||
{
|
|
||||||
// band and channel are 1-based, not 0-based
|
|
||||||
|
|
||||||
// example for raceband/ch8:
|
|
||||||
// (5 - 1) * 8 + (8 - 1)
|
|
||||||
// 4 * 8 + 7
|
|
||||||
// 32 + 7 = 39
|
|
||||||
uint8_t freqIndex = ((band - 1) * RTC6705_BAND_COUNT) + (channel - 1);
|
|
||||||
|
|
||||||
uint16_t freq = vtx_freq[freqIndex];
|
|
||||||
rtc6705SetFreq(freq);
|
|
||||||
}
|
|
||||||
|
|
||||||
void rtc6705SetRFPower(const uint8_t rf_power)
|
|
||||||
{
|
|
||||||
rtc6705_write_register(7, (rf_power ? PA_CONTROL_DEFAULT : (PA_CONTROL_DEFAULT | PD_Q5G_MASK) & (~(PA5G_PW_MASK | PA5G_BS_MASK))));
|
|
||||||
}
|
|
||||||
|
|
||||||
void rtc6705Disable(void)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
void rtc6705Enable(void)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
|
@ -67,6 +67,7 @@ extern uint8_t __config_end;
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
#include "drivers/timer.h"
|
#include "drivers/timer.h"
|
||||||
#include "drivers/usb_msc.h"
|
#include "drivers/usb_msc.h"
|
||||||
|
#include "drivers/vtx_common.h"
|
||||||
|
|
||||||
#include "fc/fc_core.h"
|
#include "fc/fc_core.h"
|
||||||
#include "fc/cli.h"
|
#include "fc/cli.h"
|
||||||
|
@ -2975,6 +2976,29 @@ static void cliStatus(char *cmdline)
|
||||||
cliPrintLinef("Arming disabled flags: 0x%lx", armingFlags & ARMING_DISABLED_ALL_FLAGS);
|
cliPrintLinef("Arming disabled flags: 0x%lx", armingFlags & ARMING_DISABLED_ALL_FLAGS);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if defined(USE_VTX_CONTROL) && !defined(CLI_MINIMAL_VERBOSITY)
|
||||||
|
cliPrint("VTX: ");
|
||||||
|
|
||||||
|
if (vtxCommonDeviceIsReady(vtxCommonDevice())) {
|
||||||
|
vtxDeviceOsdInfo_t osdInfo;
|
||||||
|
vtxCommonGetOsdInfo(vtxCommonDevice(), &osdInfo);
|
||||||
|
cliPrintf("band: %c, chan: %s, power: %c", osdInfo.bandLetter, osdInfo.channelName, osdInfo.powerIndexLetter);
|
||||||
|
|
||||||
|
if (osdInfo.powerMilliwatt) {
|
||||||
|
cliPrintf(" (%d mW)", osdInfo.powerMilliwatt);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (osdInfo.frequency) {
|
||||||
|
cliPrintf(", freq: %d MHz", osdInfo.frequency);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
cliPrint("not detected");
|
||||||
|
}
|
||||||
|
|
||||||
|
cliPrintLinefeed();
|
||||||
|
#endif
|
||||||
|
|
||||||
// If we are blocked by PWM init - provide more information
|
// If we are blocked by PWM init - provide more information
|
||||||
if (getPwmInitError() != PWM_INIT_ERROR_NONE) {
|
if (getPwmInitError() != PWM_INIT_ERROR_NONE) {
|
||||||
cliPrintLinef("PWM output init error: %s", getPwmInitErrorMessage());
|
cliPrintLinef("PWM output init error: %s", getPwmInitErrorMessage());
|
||||||
|
|
|
@ -74,7 +74,6 @@
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/exti.h"
|
#include "drivers/exti.h"
|
||||||
#include "drivers/io_pca9685.h"
|
#include "drivers/io_pca9685.h"
|
||||||
#include "drivers/vtx_rtc6705.h"
|
|
||||||
#include "drivers/vtx_common.h"
|
#include "drivers/vtx_common.h"
|
||||||
#ifdef USE_USB_MSC
|
#ifdef USE_USB_MSC
|
||||||
#include "drivers/usb_msc.h"
|
#include "drivers/usb_msc.h"
|
||||||
|
|
|
@ -2377,11 +2377,6 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
||||||
const uint8_t newChannel = (newFrequency % 8) + 1;
|
const uint8_t newChannel = (newFrequency % 8) + 1;
|
||||||
vtxSettingsConfigMutable()->band = newBand;
|
vtxSettingsConfigMutable()->band = newBand;
|
||||||
vtxSettingsConfigMutable()->channel = newChannel;
|
vtxSettingsConfigMutable()->channel = newChannel;
|
||||||
vtxSettingsConfigMutable()->freq = vtx58_Bandchan2Freq(newBand, newChannel);
|
|
||||||
} else if (newFrequency <= VTX_SETTINGS_MAX_FREQUENCY_MHZ) { //value is frequency in MHz. Ignore it if it's invalid
|
|
||||||
vtxSettingsConfigMutable()->band = 0;
|
|
||||||
vtxSettingsConfigMutable()->channel = 0;
|
|
||||||
vtxSettingsConfigMutable()->freq = newFrequency;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (sbufBytesRemaining(src) > 1) {
|
if (sbufBytesRemaining(src) > 1) {
|
||||||
|
|
|
@ -2061,16 +2061,10 @@ groups:
|
||||||
field: lowPowerDisarm
|
field: lowPowerDisarm
|
||||||
table: vtx_low_power_disarm
|
table: vtx_low_power_disarm
|
||||||
type: uint8_t
|
type: uint8_t
|
||||||
- name: vtx_freq
|
- name: vtx_pit_mode_chan
|
||||||
field: freq
|
field: pitModeChan
|
||||||
min: VTX_SETTINGS_MIN_FREQUENCY_MHZ
|
min: VTX_SETTINGS_MIN_CHANNEL
|
||||||
max: VTX_SETTINGS_MAX_FREQUENCY_MHZ
|
max: VTX_SETTINGS_MAX_CHANNEL
|
||||||
condition: VTX_SETTINGS_FREQCMD
|
|
||||||
- name: vtx_pit_mode_freq
|
|
||||||
field: pitModeFreq
|
|
||||||
min: VTX_SETTINGS_MIN_FREQUENCY_MHZ
|
|
||||||
max: VTX_SETTINGS_MAX_FREQUENCY_MHZ
|
|
||||||
condition: VTX_SETTINGS_FREQCMD
|
|
||||||
|
|
||||||
- name: PG_PINIOBOX_CONFIG
|
- name: PG_PINIOBOX_CONFIG
|
||||||
type: pinioBoxConfig_t
|
type: pinioBoxConfig_t
|
||||||
|
|
|
@ -530,14 +530,6 @@ static uint16_t osdConvertRSSI(void)
|
||||||
return constrain(getRSSI() * 100 / RSSI_MAX_VALUE, 0, 99);
|
return constrain(getRSSI() * 100 / RSSI_MAX_VALUE, 0, 99);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void osdGetVTXPowerChar(char *buff)
|
|
||||||
{
|
|
||||||
buff[0] = '-';
|
|
||||||
buff[1] = '\0';
|
|
||||||
uint8_t powerIndex = 0;
|
|
||||||
if (vtxCommonGetPowerIndex(vtxCommonDevice(), &powerIndex)) buff[0] = '0' + powerIndex;
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Displays a temperature postfixed with a symbol depending on the current unit system
|
* Displays a temperature postfixed with a symbol depending on the current unit system
|
||||||
* @param label to display
|
* @param label to display
|
||||||
|
@ -1683,34 +1675,26 @@ static bool osdDrawSingleElement(uint8_t item)
|
||||||
}
|
}
|
||||||
|
|
||||||
case OSD_VTX_CHANNEL:
|
case OSD_VTX_CHANNEL:
|
||||||
#if defined(VTX)
|
|
||||||
// FIXME: This doesn't actually work. It's for boards with
|
|
||||||
// builtin VTX.
|
|
||||||
tfp_sprintf(buff, "CH:%2d", current_vtx_channel % CHANNELS_PER_BAND + 1);
|
|
||||||
#else
|
|
||||||
{
|
{
|
||||||
uint8_t band = 0;
|
vtxDeviceOsdInfo_t osdInfo;
|
||||||
uint8_t channel = 0;
|
vtxCommonGetOsdInfo(vtxCommonDevice(), &osdInfo);
|
||||||
char bandChr = '-';
|
|
||||||
const char *channelStr = "-";
|
tfp_sprintf(buff, "CH:%c%s:", osdInfo.bandLetter, osdInfo.channelName);
|
||||||
if (vtxCommonGetBandAndChannel(vtxCommonDevice(), &band, &channel)) {
|
|
||||||
bandChr = vtx58BandLetter[band];
|
|
||||||
channelStr = vtx58ChannelNames[channel];
|
|
||||||
}
|
|
||||||
tfp_sprintf(buff, "CH:%c%s:", bandChr, channelStr);
|
|
||||||
displayWrite(osdDisplayPort, elemPosX, elemPosY, buff);
|
displayWrite(osdDisplayPort, elemPosX, elemPosY, buff);
|
||||||
|
|
||||||
osdGetVTXPowerChar(buff);
|
tfp_sprintf(buff, "%c", osdInfo.powerIndexLetter);
|
||||||
if (isAdjustmentFunctionSelected(ADJUSTMENT_VTX_POWER_LEVEL)) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
if (isAdjustmentFunctionSelected(ADJUSTMENT_VTX_POWER_LEVEL)) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
||||||
displayWriteWithAttr(osdDisplayPort, elemPosX + 6, elemPosY, buff, elemAttr);
|
displayWriteWithAttr(osdDisplayPort, elemPosX + 6, elemPosY, buff, elemAttr);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case OSD_VTX_POWER:
|
case OSD_VTX_POWER:
|
||||||
{
|
{
|
||||||
osdGetVTXPowerChar(buff);
|
vtxDeviceOsdInfo_t osdInfo;
|
||||||
|
vtxCommonGetOsdInfo(vtxCommonDevice(), &osdInfo);
|
||||||
|
|
||||||
|
tfp_sprintf(buff, "%c", osdInfo.powerIndexLetter);
|
||||||
if (isAdjustmentFunctionSelected(ADJUSTMENT_VTX_POWER_LEVEL)) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
if (isAdjustmentFunctionSelected(ADJUSTMENT_VTX_POWER_LEVEL)) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
||||||
displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr);
|
displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr);
|
||||||
return true;
|
return true;
|
||||||
|
|
|
@ -42,14 +42,13 @@
|
||||||
#include "io/vtx_string.h"
|
#include "io/vtx_string.h"
|
||||||
#include "io/vtx_control.h"
|
#include "io/vtx_control.h"
|
||||||
|
|
||||||
PG_REGISTER_WITH_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig, PG_VTX_SETTINGS_CONFIG, 0);
|
PG_REGISTER_WITH_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig, PG_VTX_SETTINGS_CONFIG, 1);
|
||||||
|
|
||||||
PG_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig,
|
PG_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig,
|
||||||
.band = VTX_SETTINGS_DEFAULT_BAND,
|
.band = VTX_SETTINGS_DEFAULT_BAND,
|
||||||
.channel = VTX_SETTINGS_DEFAULT_CHANNEL,
|
.channel = VTX_SETTINGS_DEFAULT_CHANNEL,
|
||||||
.power = VTX_SETTINGS_DEFAULT_POWER,
|
.power = VTX_SETTINGS_DEFAULT_POWER,
|
||||||
.freq = VTX_SETTINGS_DEFAULT_FREQ,
|
.pitModeChan = VTX_SETTINGS_DEFAULT_PITMODE_CHANNEL,
|
||||||
.pitModeFreq = VTX_SETTINGS_DEFAULT_PITMODE_FREQ,
|
|
||||||
.lowPowerDisarm = VTX_LOW_POWER_DISARM_OFF,
|
.lowPowerDisarm = VTX_LOW_POWER_DISARM_OFF,
|
||||||
);
|
);
|
||||||
|
|
||||||
|
@ -63,51 +62,17 @@ typedef enum {
|
||||||
|
|
||||||
void vtxInit(void)
|
void vtxInit(void)
|
||||||
{
|
{
|
||||||
bool settingsUpdated = false;
|
|
||||||
|
|
||||||
// sync frequency in parameter group when band/channel are specified
|
|
||||||
const uint16_t freq = vtx58_Bandchan2Freq(vtxSettingsConfig()->band, vtxSettingsConfig()->channel);
|
|
||||||
if (vtxSettingsConfig()->band && freq != vtxSettingsConfig()->freq) {
|
|
||||||
vtxSettingsConfigMutable()->freq = freq;
|
|
||||||
settingsUpdated = true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(VTX_SETTINGS_FREQCMD)
|
static vtxSettingsConfig_t * vtxGetRuntimeSettings(void)
|
||||||
// constrain pit mode frequency
|
|
||||||
if (vtxSettingsConfig()->pitModeFreq) {
|
|
||||||
const uint16_t constrainedPitModeFreq = MAX(vtxSettingsConfig()->pitModeFreq, VTX_SETTINGS_MIN_USER_FREQ);
|
|
||||||
if (constrainedPitModeFreq != vtxSettingsConfig()->pitModeFreq) {
|
|
||||||
vtxSettingsConfigMutable()->pitModeFreq = constrainedPitModeFreq;
|
|
||||||
settingsUpdated = true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (settingsUpdated) {
|
|
||||||
saveConfigAndNotify();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static vtxSettingsConfig_t vtxGetSettings(void)
|
|
||||||
{
|
{
|
||||||
vtxSettingsConfig_t settings = {
|
static vtxSettingsConfig_t settings;
|
||||||
.band = vtxSettingsConfig()->band,
|
|
||||||
.channel = vtxSettingsConfig()->channel,
|
|
||||||
.power = vtxSettingsConfig()->power,
|
|
||||||
.freq = vtxSettingsConfig()->freq,
|
|
||||||
.pitModeFreq = vtxSettingsConfig()->pitModeFreq,
|
|
||||||
.lowPowerDisarm = vtxSettingsConfig()->lowPowerDisarm,
|
|
||||||
};
|
|
||||||
|
|
||||||
#if 0
|
settings.band = vtxSettingsConfig()->band;
|
||||||
#if defined(VTX_SETTINGS_FREQCMD)
|
settings.channel = vtxSettingsConfig()->channel;
|
||||||
if (IS_RC_MODE_ACTIVE(BOXVTXPITMODE) && isModeActivationConditionPresent(BOXVTXPITMODE) && settings.pitModeFreq) {
|
settings.power = vtxSettingsConfig()->power;
|
||||||
settings.band = 0;
|
settings.pitModeChan = vtxSettingsConfig()->pitModeChan;
|
||||||
settings.freq = settings.pitModeFreq;
|
settings.lowPowerDisarm = vtxSettingsConfig()->lowPowerDisarm;
|
||||||
settings.power = VTX_SETTINGS_DEFAULT_POWER;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (!ARMING_FLAG(ARMED) && !failsafeIsActive() &&
|
if (!ARMING_FLAG(ARMED) && !failsafeIsActive() &&
|
||||||
((settings.lowPowerDisarm == VTX_LOW_POWER_DISARM_ALWAYS) ||
|
((settings.lowPowerDisarm == VTX_LOW_POWER_DISARM_ALWAYS) ||
|
||||||
|
@ -116,56 +81,46 @@ static vtxSettingsConfig_t vtxGetSettings(void)
|
||||||
settings.power = VTX_SETTINGS_DEFAULT_POWER;
|
settings.power = VTX_SETTINGS_DEFAULT_POWER;
|
||||||
}
|
}
|
||||||
|
|
||||||
return settings;
|
return &settings;
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool vtxProcessBandAndChannel(vtxDevice_t *vtxDevice)
|
static bool vtxProcessBandAndChannel(vtxDevice_t *vtxDevice, const vtxSettingsConfig_t * runtimeSettings)
|
||||||
{
|
{
|
||||||
|
// Shortcut for undefined band
|
||||||
|
if (!runtimeSettings->band) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
if(!ARMING_FLAG(ARMED)) {
|
if(!ARMING_FLAG(ARMED)) {
|
||||||
uint8_t vtxBand;
|
uint8_t vtxBand;
|
||||||
uint8_t vtxChan;
|
uint8_t vtxChan;
|
||||||
if (vtxCommonGetBandAndChannel(vtxDevice, &vtxBand, &vtxChan)) {
|
if (!vtxCommonGetBandAndChannel(vtxDevice, &vtxBand, &vtxChan)) {
|
||||||
const vtxSettingsConfig_t settings = vtxGetSettings();
|
return false;
|
||||||
if (vtxBand != settings.band || vtxChan != settings.channel) {
|
|
||||||
vtxCommonSetBandAndChannel(vtxDevice, settings.band, settings.channel);
|
|
||||||
return true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (vtxBand != runtimeSettings->band || vtxChan != runtimeSettings->channel) {
|
||||||
|
vtxCommonSetBandAndChannel(vtxDevice, runtimeSettings->band, runtimeSettings->channel);
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(VTX_SETTINGS_FREQCMD)
|
static bool vtxProcessPower(vtxDevice_t *vtxDevice, const vtxSettingsConfig_t * runtimeSettings)
|
||||||
static bool vtxProcessFrequency(vtxDevice_t *vtxDevice)
|
|
||||||
{
|
|
||||||
if(!ARMING_FLAG(ARMED)) {
|
|
||||||
uint16_t vtxFreq;
|
|
||||||
if (vtxCommonGetFrequency(vtxDevice, &vtxFreq)) {
|
|
||||||
const vtxSettingsConfig_t settings = vtxGetSettings();
|
|
||||||
if (vtxFreq != settings.freq) {
|
|
||||||
vtxCommonSetFrequency(vtxDevice, settings.freq);
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
static bool vtxProcessPower(vtxDevice_t *vtxDevice)
|
|
||||||
{
|
{
|
||||||
uint8_t vtxPower;
|
uint8_t vtxPower;
|
||||||
if (vtxCommonGetPowerIndex(vtxDevice, &vtxPower)) {
|
if (!vtxCommonGetPowerIndex(vtxDevice, &vtxPower)) {
|
||||||
const vtxSettingsConfig_t settings = vtxGetSettings();
|
return false;
|
||||||
if (vtxPower != settings.power) {
|
|
||||||
vtxCommonSetPowerByIndex(vtxDevice, settings.power);
|
|
||||||
return true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (vtxPower != runtimeSettings->power) {
|
||||||
|
vtxCommonSetPowerByIndex(vtxDevice, runtimeSettings->power);
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool vtxProcessPitMode(vtxDevice_t *vtxDevice)
|
static bool vtxProcessPitMode(vtxDevice_t *vtxDevice, const vtxSettingsConfig_t * runtimeSettings)
|
||||||
{
|
{
|
||||||
uint8_t pitOnOff;
|
uint8_t pitOnOff;
|
||||||
|
|
||||||
|
@ -173,25 +128,10 @@ static bool vtxProcessPitMode(vtxDevice_t *vtxDevice)
|
||||||
static bool prevPmSwitchState = false;
|
static bool prevPmSwitchState = false;
|
||||||
|
|
||||||
if (!ARMING_FLAG(ARMED) && vtxCommonGetPitMode(vtxDevice, &pitOnOff)) {
|
if (!ARMING_FLAG(ARMED) && vtxCommonGetPitMode(vtxDevice, &pitOnOff)) {
|
||||||
|
|
||||||
// Not supported on INAV yet. It might not be that useful.
|
|
||||||
#if 0
|
|
||||||
currPmSwitchState = IS_RC_MODE_ACTIVE(BOXVTXPITMODE);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (currPmSwitchState != prevPmSwitchState) {
|
if (currPmSwitchState != prevPmSwitchState) {
|
||||||
prevPmSwitchState = currPmSwitchState;
|
prevPmSwitchState = currPmSwitchState;
|
||||||
|
|
||||||
if (currPmSwitchState) {
|
if (currPmSwitchState) {
|
||||||
#if defined(VTX_SETTINGS_FREQCMD)
|
|
||||||
if (vtxSettingsConfig()->pitModeFreq) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if 0
|
|
||||||
if (isModeActivationConditionPresent(BOXVTXPITMODE)) {
|
|
||||||
#endif
|
|
||||||
if (0) {
|
if (0) {
|
||||||
if (!pitOnOff) {
|
if (!pitOnOff) {
|
||||||
vtxCommonSetPitMode(vtxDevice, true);
|
vtxCommonSetPitMode(vtxDevice, true);
|
||||||
|
@ -209,22 +149,18 @@ static bool vtxProcessPitMode(vtxDevice_t *vtxDevice)
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool vtxProcessStateUpdate(vtxDevice_t *vtxDevice)
|
static bool vtxProcessCheckParameters(vtxDevice_t *vtxDevice, const vtxSettingsConfig_t * runtimeSettings)
|
||||||
{
|
{
|
||||||
const vtxSettingsConfig_t vtxSettingsState = vtxGetSettings();
|
uint8_t vtxBand;
|
||||||
vtxSettingsConfig_t vtxState = vtxSettingsState;
|
uint8_t vtxChan;
|
||||||
|
uint8_t vtxPower;
|
||||||
|
|
||||||
if (vtxSettingsState.band) {
|
vtxCommonGetPowerIndex(vtxDevice, &vtxPower);
|
||||||
vtxCommonGetBandAndChannel(vtxDevice, &vtxState.band, &vtxState.channel);
|
vtxCommonGetBandAndChannel(vtxDevice, &vtxBand, &vtxChan);
|
||||||
#if defined(VTX_SETTINGS_FREQCMD)
|
|
||||||
} else {
|
|
||||||
vtxCommonGetFrequency(vtxDevice, &vtxState.freq);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
vtxCommonGetPowerIndex(vtxDevice, &vtxState.power);
|
return (runtimeSettings->band && runtimeSettings->band != vtxBand) ||
|
||||||
|
(runtimeSettings->channel != vtxChan) ||
|
||||||
return (bool)memcmp(&vtxSettingsState, &vtxState, sizeof(vtxSettingsConfig_t));
|
(runtimeSettings->power != vtxPower);
|
||||||
}
|
}
|
||||||
|
|
||||||
void vtxUpdate(timeUs_t currentTimeUs)
|
void vtxUpdate(timeUs_t currentTimeUs)
|
||||||
|
@ -240,36 +176,32 @@ void vtxUpdate(timeUs_t currentTimeUs)
|
||||||
// Check input sources for config updates
|
// Check input sources for config updates
|
||||||
vtxControlInputPoll();
|
vtxControlInputPoll();
|
||||||
|
|
||||||
const uint8_t startingSchedule = currentSchedule;
|
// Build runtime settings
|
||||||
|
const vtxSettingsConfig_t * runtimeSettings = vtxGetRuntimeSettings();
|
||||||
|
|
||||||
bool vtxUpdatePending = false;
|
bool vtxUpdatePending = false;
|
||||||
do {
|
|
||||||
switch (currentSchedule) {
|
switch (currentSchedule) {
|
||||||
case VTX_PARAM_POWER:
|
case VTX_PARAM_POWER:
|
||||||
vtxUpdatePending = vtxProcessPower(vtxDevice);
|
vtxUpdatePending = vtxProcessPower(vtxDevice, runtimeSettings);
|
||||||
break;
|
break;
|
||||||
case VTX_PARAM_BANDCHAN:
|
case VTX_PARAM_BANDCHAN:
|
||||||
if (vtxGetSettings().band) {
|
vtxUpdatePending = vtxProcessBandAndChannel(vtxDevice, runtimeSettings);
|
||||||
vtxUpdatePending = vtxProcessBandAndChannel(vtxDevice);
|
|
||||||
#if defined(VTX_SETTINGS_FREQCMD)
|
|
||||||
} else {
|
|
||||||
vtxUpdatePending = vtxProcessFrequency(vtxDevice);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
break;
|
break;
|
||||||
case VTX_PARAM_PITMODE:
|
case VTX_PARAM_PITMODE:
|
||||||
vtxUpdatePending = vtxProcessPitMode(vtxDevice);
|
vtxUpdatePending = vtxProcessPitMode(vtxDevice, runtimeSettings);
|
||||||
break;
|
break;
|
||||||
case VTX_PARAM_CONFIRM:
|
case VTX_PARAM_CONFIRM:
|
||||||
vtxUpdatePending = vtxProcessStateUpdate(vtxDevice);
|
vtxUpdatePending = vtxProcessCheckParameters(vtxDevice, runtimeSettings);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
currentSchedule = (currentSchedule + 1) % VTX_PARAM_COUNT;
|
|
||||||
} while (!vtxUpdatePending && currentSchedule != startingSchedule);
|
|
||||||
|
|
||||||
if (!ARMING_FLAG(ARMED) || vtxUpdatePending) {
|
if (!ARMING_FLAG(ARMED) || vtxUpdatePending) {
|
||||||
vtxCommonProcess(vtxDevice, currentTimeUs);
|
vtxCommonProcess(vtxDevice, currentTimeUs);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
currentSchedule = (currentSchedule + 1) % VTX_PARAM_COUNT;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -38,8 +38,7 @@ typedef struct vtxSettingsConfig_s {
|
||||||
uint8_t band; // 1=A, 2=B, 3=E, 4=F(Airwaves/Fatshark), 5=Racebande
|
uint8_t band; // 1=A, 2=B, 3=E, 4=F(Airwaves/Fatshark), 5=Racebande
|
||||||
uint8_t channel; // 1-8
|
uint8_t channel; // 1-8
|
||||||
uint8_t power; // 0 = lowest
|
uint8_t power; // 0 = lowest
|
||||||
uint16_t freq; // sets freq in MHz if band=0
|
uint16_t pitModeChan; // sets out-of-range pitmode frequency
|
||||||
uint16_t pitModeFreq; // sets out-of-range pitmode frequency
|
|
||||||
uint8_t lowPowerDisarm; // min power while disarmed, from vtxLowerPowerDisarm_e
|
uint8_t lowPowerDisarm; // min power while disarmed, from vtxLowerPowerDisarm_e
|
||||||
} vtxSettingsConfig_t;
|
} vtxSettingsConfig_t;
|
||||||
|
|
||||||
|
|
|
@ -42,7 +42,6 @@
|
||||||
PG_REGISTER_WITH_RESET_TEMPLATE(vtxConfig_t, vtxConfig, PG_VTX_CONFIG, 2);
|
PG_REGISTER_WITH_RESET_TEMPLATE(vtxConfig_t, vtxConfig, PG_VTX_CONFIG, 2);
|
||||||
|
|
||||||
PG_RESET_TEMPLATE(vtxConfig_t, vtxConfig,
|
PG_RESET_TEMPLATE(vtxConfig_t, vtxConfig,
|
||||||
// .vtxChannelActivationConditions = { 0 },
|
|
||||||
.halfDuplex = true,
|
.halfDuplex = true,
|
||||||
);
|
);
|
||||||
|
|
||||||
|
|
|
@ -33,15 +33,6 @@ typedef struct vtxConfig_s {
|
||||||
uint8_t halfDuplex;
|
uint8_t halfDuplex;
|
||||||
} vtxConfig_t;
|
} vtxConfig_t;
|
||||||
|
|
||||||
typedef struct vtxRunState_s {
|
|
||||||
int pitMode;
|
|
||||||
int band;
|
|
||||||
int channel;
|
|
||||||
int frequency;
|
|
||||||
int powerIndex;
|
|
||||||
int powerMilliwatt;
|
|
||||||
} vtxRunState_t;
|
|
||||||
|
|
||||||
PG_DECLARE(vtxConfig_t, vtxConfig);
|
PG_DECLARE(vtxConfig_t, vtxConfig);
|
||||||
|
|
||||||
void vtxControlInit(void);
|
void vtxControlInit(void);
|
||||||
|
|
|
@ -41,8 +41,6 @@
|
||||||
|
|
||||||
#include "scheduler/protothreads.h"
|
#include "scheduler/protothreads.h"
|
||||||
|
|
||||||
//#include "cms/cms_menu_vtx_ffpv24g.h"
|
|
||||||
|
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
#include "io/vtx_ffpv24g.h"
|
#include "io/vtx_ffpv24g.h"
|
||||||
#include "io/vtx_control.h"
|
#include "io/vtx_control.h"
|
||||||
|
@ -85,7 +83,6 @@ typedef struct {
|
||||||
|
|
||||||
// Requested VTX state
|
// Requested VTX state
|
||||||
struct {
|
struct {
|
||||||
bool setByFrequency;
|
|
||||||
int band;
|
int band;
|
||||||
int channel;
|
int channel;
|
||||||
unsigned freq;
|
unsigned freq;
|
||||||
|
@ -108,9 +105,9 @@ typedef struct {
|
||||||
|
|
||||||
/*****************************************************************************/
|
/*****************************************************************************/
|
||||||
const char * const ffpvBandNames[VTX_FFPV_BAND_COUNT + 1] = {
|
const char * const ffpvBandNames[VTX_FFPV_BAND_COUNT + 1] = {
|
||||||
"--------",
|
"-----",
|
||||||
"FFPV 2.4 A",
|
"A 2.4",
|
||||||
"FFPV 2.4 B",
|
"B 2.4",
|
||||||
};
|
};
|
||||||
|
|
||||||
const char * ffpvBandLetters = "-AB";
|
const char * ffpvBandLetters = "-AB";
|
||||||
|
@ -353,18 +350,10 @@ static bool impl_DevSetFreq(uint16_t freq)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void impl_SetFreq(vtxDevice_t * vtxDevice, uint16_t freq)
|
static void impl_SetBandAndChannel(vtxDevice_t * vtxDevice, uint8_t band, uint8_t channel)
|
||||||
{
|
{
|
||||||
UNUSED(vtxDevice);
|
UNUSED(vtxDevice);
|
||||||
|
|
||||||
if (impl_DevSetFreq(freq)) {
|
|
||||||
// Keep track that we set frequency directly
|
|
||||||
vtxState.request.setByFrequency = true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void ffpvSetBandAndChannel(uint8_t band, uint8_t channel)
|
|
||||||
{
|
|
||||||
// Validate band and channel
|
// Validate band and channel
|
||||||
if (band < VTX_FFPV_MIN_BAND || band > VTX_FFPV_MAX_BAND || channel < VTX_FFPV_MIN_CHANNEL || channel > VTX_FFPV_MAX_CHANNEL) {
|
if (band < VTX_FFPV_MIN_BAND || band > VTX_FFPV_MAX_BAND || channel < VTX_FFPV_MIN_CHANNEL || channel > VTX_FFPV_MAX_CHANNEL) {
|
||||||
return;
|
return;
|
||||||
|
@ -372,20 +361,12 @@ void ffpvSetBandAndChannel(uint8_t band, uint8_t channel)
|
||||||
|
|
||||||
if (impl_DevSetFreq(ffpvFrequencyTable[band - 1][channel - 1])) {
|
if (impl_DevSetFreq(ffpvFrequencyTable[band - 1][channel - 1])) {
|
||||||
// Keep track of band/channel data
|
// Keep track of band/channel data
|
||||||
vtxState.request.setByFrequency = false;
|
|
||||||
vtxState.request.band = band;
|
vtxState.request.band = band;
|
||||||
vtxState.request.channel = channel;
|
vtxState.request.channel = channel;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void ffpvSetRFPowerByIndex(uint16_t index)
|
||||||
static void impl_SetBandAndChannel(vtxDevice_t * vtxDevice, uint8_t band, uint8_t channel)
|
|
||||||
{
|
|
||||||
UNUSED(vtxDevice);
|
|
||||||
ffpvSetBandAndChannel(band, channel);
|
|
||||||
}
|
|
||||||
|
|
||||||
void ffpvSetRFPowerByIndex(uint16_t index)
|
|
||||||
{
|
{
|
||||||
// Validate index
|
// Validate index
|
||||||
if (index < 1 || index > VTX_FFPV_POWER_COUNT) {
|
if (index < 1 || index > VTX_FFPV_POWER_COUNT) {
|
||||||
|
@ -422,7 +403,7 @@ static bool impl_GetBandAndChannel(const vtxDevice_t *vtxDevice, uint8_t *pBand,
|
||||||
}
|
}
|
||||||
|
|
||||||
// if in user-freq mode then report band as zero
|
// if in user-freq mode then report band as zero
|
||||||
*pBand = vtxState.request.setByFrequency ? 0 : vtxState.request.band;
|
*pBand = vtxState.request.band;
|
||||||
*pChannel = vtxState.request.channel;
|
*pChannel = vtxState.request.channel;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -459,27 +440,33 @@ static bool impl_GetFreq(const vtxDevice_t *vtxDevice, uint16_t *pFreq)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
vtxRunState_t * ffpvGetRuntimeState(void)
|
static bool impl_GetPower(const vtxDevice_t *vtxDevice, uint8_t *pIndex, uint16_t *pPowerMw)
|
||||||
{
|
{
|
||||||
static vtxRunState_t state;
|
if (!impl_IsReady(vtxDevice)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
if (vtxState.ready) {
|
*pIndex = vtxState.request.powerIndex;
|
||||||
state.pitMode = 0;
|
*pPowerMw = vtxState.request.power;
|
||||||
state.band = vtxState.request.band;
|
return true;
|
||||||
state.channel = vtxState.request.channel;
|
|
||||||
state.frequency = vtxState.request.freq;
|
|
||||||
state.powerIndex = vtxState.request.powerIndex;
|
|
||||||
state.powerMilliwatt = vtxState.request.power;
|
|
||||||
}
|
}
|
||||||
else {
|
|
||||||
state.pitMode = 0;
|
static bool impl_GetOsdInfo(const vtxDevice_t *vtxDevice, vtxDeviceOsdInfo_t * pOsdInfo)
|
||||||
state.band = 1;
|
{
|
||||||
state.channel = 1;
|
if (!impl_IsReady(vtxDevice)) {
|
||||||
state.frequency = ffpvFrequencyTable[0][0];
|
return false;
|
||||||
state.powerIndex = 1;
|
|
||||||
state.powerMilliwatt = 25;
|
|
||||||
}
|
}
|
||||||
return &state;
|
|
||||||
|
pOsdInfo->band = vtxState.request.band;
|
||||||
|
pOsdInfo->channel = vtxState.request.channel;
|
||||||
|
pOsdInfo->frequency = vtxState.request.freq;
|
||||||
|
pOsdInfo->powerIndex = vtxState.request.powerIndex;
|
||||||
|
pOsdInfo->powerMilliwatt = vtxState.request.power;
|
||||||
|
pOsdInfo->bandName = ffpvBandNames[vtxState.request.band];
|
||||||
|
pOsdInfo->bandLetter = ffpvBandLetters[vtxState.request.band];
|
||||||
|
pOsdInfo->channelName = ffpvChannelNames[vtxState.request.channel];
|
||||||
|
pOsdInfo->powerIndexLetter = '0' + vtxState.request.powerIndex;
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*****************************************************************************/
|
/*****************************************************************************/
|
||||||
|
@ -490,11 +477,12 @@ static const vtxVTable_t impl_vtxVTable = {
|
||||||
.setBandAndChannel = impl_SetBandAndChannel,
|
.setBandAndChannel = impl_SetBandAndChannel,
|
||||||
.setPowerByIndex = impl_SetPowerByIndex,
|
.setPowerByIndex = impl_SetPowerByIndex,
|
||||||
.setPitMode = impl_SetPitMode,
|
.setPitMode = impl_SetPitMode,
|
||||||
.setFrequency = impl_SetFreq,
|
|
||||||
.getBandAndChannel = impl_GetBandAndChannel,
|
.getBandAndChannel = impl_GetBandAndChannel,
|
||||||
.getPowerIndex = impl_GetPowerIndex,
|
.getPowerIndex = impl_GetPowerIndex,
|
||||||
.getPitMode = impl_GetPitMode,
|
.getPitMode = impl_GetPitMode,
|
||||||
.getFrequency = impl_GetFreq,
|
.getFrequency = impl_GetFreq,
|
||||||
|
.getPower = impl_GetPower,
|
||||||
|
.getOsdInfo = impl_GetOsdInfo,
|
||||||
};
|
};
|
||||||
|
|
||||||
static vtxDevice_t impl_vtxDevice = {
|
static vtxDevice_t impl_vtxDevice = {
|
||||||
|
@ -502,9 +490,9 @@ static vtxDevice_t impl_vtxDevice = {
|
||||||
.capability.bandCount = VTX_FFPV_BAND_COUNT,
|
.capability.bandCount = VTX_FFPV_BAND_COUNT,
|
||||||
.capability.channelCount = VTX_FFPV_CHANNEL_COUNT,
|
.capability.channelCount = VTX_FFPV_CHANNEL_COUNT,
|
||||||
.capability.powerCount = VTX_FFPV_POWER_COUNT,
|
.capability.powerCount = VTX_FFPV_POWER_COUNT,
|
||||||
.bandNames = (char **)ffpvBandNames,
|
.capability.bandNames = (char **)ffpvBandNames,
|
||||||
.channelNames = (char **)ffpvChannelNames,
|
.capability.channelNames = (char **)ffpvChannelNames,
|
||||||
.powerNames = (char **)ffpvPowerNames,
|
.capability.powerNames = (char **)ffpvPowerNames,
|
||||||
};
|
};
|
||||||
|
|
||||||
bool vtxFuriousFPVInit(void)
|
bool vtxFuriousFPVInit(void)
|
||||||
|
|
|
@ -38,14 +38,4 @@
|
||||||
#define VTX_FFPV_CHANNEL_COUNT 8
|
#define VTX_FFPV_CHANNEL_COUNT 8
|
||||||
#define VTX_FFPV_POWER_COUNT 4
|
#define VTX_FFPV_POWER_COUNT 4
|
||||||
|
|
||||||
extern const char * ffpvBandLetters;
|
|
||||||
extern const char * const ffpvBandNames[VTX_FFPV_BAND_COUNT + 1];
|
|
||||||
extern const char * const ffpvChannelNames[VTX_FFPV_CHANNEL_COUNT + 1];
|
|
||||||
extern const char * const ffpvPowerNames[VTX_FFPV_POWER_COUNT + 1];
|
|
||||||
extern const uint16_t ffpvFrequencyTable[VTX_FFPV_BAND_COUNT][VTX_FFPV_CHANNEL_COUNT];
|
|
||||||
|
|
||||||
bool vtxFuriousFPVInit(void);
|
bool vtxFuriousFPVInit(void);
|
||||||
void ffpvSetBandAndChannel(uint8_t band, uint8_t channel);
|
|
||||||
void ffpvSetRFPowerByIndex(uint16_t index);
|
|
||||||
|
|
||||||
vtxRunState_t * ffpvGetRuntimeState(void);
|
|
|
@ -32,7 +32,6 @@
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
|
|
||||||
#include "cms/cms.h"
|
#include "cms/cms.h"
|
||||||
#include "cms/cms_menu_vtx_smartaudio.h"
|
|
||||||
|
|
||||||
#include "common/log.h"
|
#include "common/log.h"
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
@ -67,9 +66,9 @@ static vtxDevice_t vtxSmartAudio = {
|
||||||
.capability.bandCount = VTX_SMARTAUDIO_BAND_COUNT,
|
.capability.bandCount = VTX_SMARTAUDIO_BAND_COUNT,
|
||||||
.capability.channelCount = VTX_SMARTAUDIO_CHANNEL_COUNT,
|
.capability.channelCount = VTX_SMARTAUDIO_CHANNEL_COUNT,
|
||||||
.capability.powerCount = VTX_SMARTAUDIO_POWER_COUNT,
|
.capability.powerCount = VTX_SMARTAUDIO_POWER_COUNT,
|
||||||
.bandNames = (char **)vtx58BandNames,
|
.capability.bandNames = (char **)vtx58BandNames,
|
||||||
.channelNames = (char **)vtx58ChannelNames,
|
.capability.channelNames = (char **)vtx58ChannelNames,
|
||||||
.powerNames = (char **)saPowerNames,
|
.capability.powerNames = (char **)saPowerNames,
|
||||||
};
|
};
|
||||||
|
|
||||||
// SmartAudio command and response codes
|
// SmartAudio command and response codes
|
||||||
|
@ -332,7 +331,7 @@ static void saProcessResponse(uint8_t *buf, int len)
|
||||||
|
|
||||||
if (memcmp(&saDevice, &saDevicePrev, sizeof(smartAudioDevice_t))) {
|
if (memcmp(&saDevice, &saDevicePrev, sizeof(smartAudioDevice_t))) {
|
||||||
#ifdef USE_CMS //if changes then trigger saCms update
|
#ifdef USE_CMS //if changes then trigger saCms update
|
||||||
saCmsResetOpmodel();
|
//saCmsResetOpmodel();
|
||||||
#endif
|
#endif
|
||||||
// Debug
|
// Debug
|
||||||
saPrintSettings();
|
saPrintSettings();
|
||||||
|
@ -341,7 +340,7 @@ static void saProcessResponse(uint8_t *buf, int len)
|
||||||
|
|
||||||
#ifdef USE_CMS
|
#ifdef USE_CMS
|
||||||
// Export current device status for CMS
|
// Export current device status for CMS
|
||||||
saCmsUpdate();
|
//saCmsUpdate();
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -540,11 +539,6 @@ static void saGetSettings(void)
|
||||||
saQueueCmd(bufGetSettings, 5);
|
saQueueCmd(bufGetSettings, 5);
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool saValidateFreq(uint16_t freq)
|
|
||||||
{
|
|
||||||
return (freq >= VTX_SMARTAUDIO_MIN_FREQUENCY_MHZ && freq <= VTX_SMARTAUDIO_MAX_FREQUENCY_MHZ);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void saDoDevSetFreq(uint16_t freq)
|
static void saDoDevSetFreq(uint16_t freq)
|
||||||
{
|
{
|
||||||
static uint8_t buf[7] = { 0xAA, 0x55, SACMD(SA_CMD_SET_FREQ), 2 };
|
static uint8_t buf[7] = { 0xAA, 0x55, SACMD(SA_CMD_SET_FREQ), 2 };
|
||||||
|
@ -802,15 +796,6 @@ static void vtxSASetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void vtxSASetFreq(vtxDevice_t *vtxDevice, uint16_t freq)
|
|
||||||
{
|
|
||||||
UNUSED(vtxDevice);
|
|
||||||
if (saValidateFreq(freq)) {
|
|
||||||
saSetMode(0); //need to be in FREE mode to set freq
|
|
||||||
saSetFreq(freq);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static bool vtxSAGetBandAndChannel(const vtxDevice_t *vtxDevice, uint8_t *pBand, uint8_t *pChannel)
|
static bool vtxSAGetBandAndChannel(const vtxDevice_t *vtxDevice, uint8_t *pBand, uint8_t *pChannel)
|
||||||
{
|
{
|
||||||
if (!vtxSAIsReady(vtxDevice)) {
|
if (!vtxSAIsReady(vtxDevice)) {
|
||||||
|
@ -857,6 +842,50 @@ static bool vtxSAGetFreq(const vtxDevice_t *vtxDevice, uint16_t *pFreq)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static bool vtxSAGetPower(const vtxDevice_t *vtxDevice, uint8_t *pIndex, uint16_t *pPowerMw)
|
||||||
|
{
|
||||||
|
uint8_t powerIndex;
|
||||||
|
|
||||||
|
if (!vtxSAGetPowerIndex(vtxDevice, &powerIndex)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
*pIndex = powerIndex;
|
||||||
|
*pPowerMw = (powerIndex > 0) ? saPowerTable[powerIndex-1].rfpower : 0;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool vtxSAGetOsdInfo(const vtxDevice_t *vtxDevice, vtxDeviceOsdInfo_t * pOsdInfo)
|
||||||
|
{
|
||||||
|
uint8_t powerIndex;
|
||||||
|
uint16_t powerMw;
|
||||||
|
uint16_t freq;
|
||||||
|
uint8_t band, channel;
|
||||||
|
|
||||||
|
if (!vtxSAGetBandAndChannel(vtxDevice, &band, &channel)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!vtxSAGetFreq(vtxDevice, &freq)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!vtxSAGetPower(vtxDevice, &powerIndex, &powerMw)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
pOsdInfo->band = band;
|
||||||
|
pOsdInfo->channel = channel;
|
||||||
|
pOsdInfo->frequency = freq;
|
||||||
|
pOsdInfo->powerIndex = powerIndex;
|
||||||
|
pOsdInfo->powerMilliwatt = powerMw;
|
||||||
|
pOsdInfo->bandLetter = vtx58BandNames[band][0];
|
||||||
|
pOsdInfo->bandName = vtx58BandNames[band];
|
||||||
|
pOsdInfo->channelName = vtx58ChannelNames[channel];
|
||||||
|
pOsdInfo->powerIndexLetter = '0' + powerIndex;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
static const vtxVTable_t saVTable = {
|
static const vtxVTable_t saVTable = {
|
||||||
.process = vtxSAProcess,
|
.process = vtxSAProcess,
|
||||||
.getDeviceType = vtxSAGetDeviceType,
|
.getDeviceType = vtxSAGetDeviceType,
|
||||||
|
@ -864,11 +893,12 @@ static const vtxVTable_t saVTable = {
|
||||||
.setBandAndChannel = vtxSASetBandAndChannel,
|
.setBandAndChannel = vtxSASetBandAndChannel,
|
||||||
.setPowerByIndex = vtxSASetPowerByIndex,
|
.setPowerByIndex = vtxSASetPowerByIndex,
|
||||||
.setPitMode = vtxSASetPitMode,
|
.setPitMode = vtxSASetPitMode,
|
||||||
.setFrequency = vtxSASetFreq,
|
|
||||||
.getBandAndChannel = vtxSAGetBandAndChannel,
|
.getBandAndChannel = vtxSAGetBandAndChannel,
|
||||||
.getPowerIndex = vtxSAGetPowerIndex,
|
.getPowerIndex = vtxSAGetPowerIndex,
|
||||||
.getPitMode = vtxSAGetPitMode,
|
.getPitMode = vtxSAGetPitMode,
|
||||||
.getFrequency = vtxSAGetFreq,
|
.getFrequency = vtxSAGetFreq,
|
||||||
|
.getPower = vtxSAGetPower,
|
||||||
|
.getOsdInfo = vtxSAGetOsdInfo,
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -27,6 +27,7 @@
|
||||||
|
|
||||||
#define VTX_STRING_BAND_COUNT 5
|
#define VTX_STRING_BAND_COUNT 5
|
||||||
#define VTX_STRING_CHAN_COUNT 8
|
#define VTX_STRING_CHAN_COUNT 8
|
||||||
|
#define VTX_STRING_POWER_COUNT 5
|
||||||
|
|
||||||
const uint16_t vtx58frequencyTable[VTX_STRING_BAND_COUNT][VTX_STRING_CHAN_COUNT] =
|
const uint16_t vtx58frequencyTable[VTX_STRING_BAND_COUNT][VTX_STRING_CHAN_COUNT] =
|
||||||
{
|
{
|
||||||
|
@ -52,6 +53,10 @@ const char * const vtx58ChannelNames[VTX_STRING_CHAN_COUNT + 1] = {
|
||||||
"-", "1", "2", "3", "4", "5", "6", "7", "8",
|
"-", "1", "2", "3", "4", "5", "6", "7", "8",
|
||||||
};
|
};
|
||||||
|
|
||||||
|
const char * const vtx58DefaultPowerNames[VTX_STRING_POWER_COUNT + 1] = {
|
||||||
|
"---", "PL1", "PL2", "PL3", "PL4", "PL5"
|
||||||
|
};
|
||||||
|
|
||||||
bool vtx58_Freq2Bandchan(uint16_t freq, uint8_t *pBand, uint8_t *pChannel)
|
bool vtx58_Freq2Bandchan(uint16_t freq, uint8_t *pBand, uint8_t *pChannel)
|
||||||
{
|
{
|
||||||
int8_t band;
|
int8_t band;
|
||||||
|
|
|
@ -5,6 +5,7 @@
|
||||||
extern const uint16_t vtx58frequencyTable[5][8];
|
extern const uint16_t vtx58frequencyTable[5][8];
|
||||||
extern const char * const vtx58BandNames[];
|
extern const char * const vtx58BandNames[];
|
||||||
extern const char * const vtx58ChannelNames[];
|
extern const char * const vtx58ChannelNames[];
|
||||||
|
extern const char * const vtx58DefaultPowerNames[];
|
||||||
extern const char vtx58BandLetter[];
|
extern const char vtx58BandLetter[];
|
||||||
|
|
||||||
bool vtx58_Freq2Bandchan(uint16_t freq, uint8_t *pBand, uint8_t *pChannel);
|
bool vtx58_Freq2Bandchan(uint16_t freq, uint8_t *pBand, uint8_t *pChannel);
|
||||||
|
|
|
@ -34,8 +34,6 @@
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "cms/cms_menu_vtx_tramp.h"
|
|
||||||
|
|
||||||
#include "drivers/vtx_common.h"
|
#include "drivers/vtx_common.h"
|
||||||
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
@ -44,7 +42,6 @@
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
#include "io/vtx_string.h"
|
#include "io/vtx_string.h"
|
||||||
|
|
||||||
#if defined(USE_CMS)
|
|
||||||
const uint16_t trampPowerTable[VTX_TRAMP_POWER_COUNT] = {
|
const uint16_t trampPowerTable[VTX_TRAMP_POWER_COUNT] = {
|
||||||
25, 100, 200, 400, 600
|
25, 100, 200, 400, 600
|
||||||
};
|
};
|
||||||
|
@ -52,7 +49,6 @@ const uint16_t trampPowerTable[VTX_TRAMP_POWER_COUNT] = {
|
||||||
const char * const trampPowerNames[VTX_TRAMP_POWER_COUNT+1] = {
|
const char * const trampPowerNames[VTX_TRAMP_POWER_COUNT+1] = {
|
||||||
"---", "25 ", "100", "200", "400", "600"
|
"---", "25 ", "100", "200", "400", "600"
|
||||||
};
|
};
|
||||||
#endif
|
|
||||||
|
|
||||||
static const vtxVTable_t trampVTable; // forward
|
static const vtxVTable_t trampVTable; // forward
|
||||||
static vtxDevice_t vtxTramp = {
|
static vtxDevice_t vtxTramp = {
|
||||||
|
@ -60,9 +56,9 @@ static vtxDevice_t vtxTramp = {
|
||||||
.capability.bandCount = VTX_TRAMP_BAND_COUNT,
|
.capability.bandCount = VTX_TRAMP_BAND_COUNT,
|
||||||
.capability.channelCount = VTX_TRAMP_CHANNEL_COUNT,
|
.capability.channelCount = VTX_TRAMP_CHANNEL_COUNT,
|
||||||
.capability.powerCount = VTX_TRAMP_POWER_COUNT,
|
.capability.powerCount = VTX_TRAMP_POWER_COUNT,
|
||||||
.bandNames = (char **)vtx58BandNames,
|
.capability.bandNames = (char **)vtx58BandNames,
|
||||||
.channelNames = (char **)vtx58ChannelNames,
|
.capability.channelNames = (char **)vtx58ChannelNames,
|
||||||
.powerNames = (char **)trampPowerNames,
|
.capability.powerNames = (char **)trampPowerNames,
|
||||||
};
|
};
|
||||||
|
|
||||||
static serialPort_t *trampSerialPort = NULL;
|
static serialPort_t *trampSerialPort = NULL;
|
||||||
|
@ -126,11 +122,6 @@ void trampCmdU16(uint8_t cmd, uint16_t param)
|
||||||
trampWriteBuf(trampReqBuffer);
|
trampWriteBuf(trampReqBuffer);
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool trampValidateFreq(uint16_t freq)
|
|
||||||
{
|
|
||||||
return (freq >= VTX_TRAMP_MIN_FREQUENCY_MHZ && freq <= VTX_TRAMP_MAX_FREQUENCY_MHZ);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void trampDevSetFreq(uint16_t freq)
|
static void trampDevSetFreq(uint16_t freq)
|
||||||
{
|
{
|
||||||
trampConfFreq = freq;
|
trampConfFreq = freq;
|
||||||
|
@ -511,15 +502,6 @@ static void vtxTrampSetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff)
|
||||||
trampSetPitMode(onoff);
|
trampSetPitMode(onoff);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void vtxTrampSetFreq(vtxDevice_t *vtxDevice, uint16_t freq)
|
|
||||||
{
|
|
||||||
UNUSED(vtxDevice);
|
|
||||||
if (trampValidateFreq(freq)) {
|
|
||||||
trampSetFreq(freq);
|
|
||||||
trampCommitChanges();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static bool vtxTrampGetBandAndChannel(const vtxDevice_t *vtxDevice, uint8_t *pBand, uint8_t *pChannel)
|
static bool vtxTrampGetBandAndChannel(const vtxDevice_t *vtxDevice, uint8_t *pBand, uint8_t *pChannel)
|
||||||
{
|
{
|
||||||
if (!vtxTrampIsReady(vtxDevice)) {
|
if (!vtxTrampIsReady(vtxDevice)) {
|
||||||
|
@ -570,6 +552,40 @@ static bool vtxTrampGetFreq(const vtxDevice_t *vtxDevice, uint16_t *pFreq)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static bool vtxTrampGetPower(const vtxDevice_t *vtxDevice, uint8_t *pIndex, uint16_t *pPowerMw)
|
||||||
|
{
|
||||||
|
uint8_t powerIndex;
|
||||||
|
if (!vtxTrampGetPowerIndex(vtxDevice, &powerIndex)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
*pIndex = trampData.configuredPower ? powerIndex : 0;
|
||||||
|
*pPowerMw = trampData.configuredPower;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool vtxTrampGetOsdInfo(const vtxDevice_t *vtxDevice, vtxDeviceOsdInfo_t * pOsdInfo)
|
||||||
|
{
|
||||||
|
uint8_t powerIndex;
|
||||||
|
uint16_t powerMw;
|
||||||
|
|
||||||
|
if (!vtxTrampGetPower(vtxDevice, &powerIndex, &powerMw)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
pOsdInfo->band = trampData.setByFreqFlag ? 0 : trampData.band;
|
||||||
|
pOsdInfo->channel = trampData.channel;
|
||||||
|
pOsdInfo->frequency = trampData.curFreq;
|
||||||
|
pOsdInfo->powerIndex = powerIndex;
|
||||||
|
pOsdInfo->powerMilliwatt = powerMw;
|
||||||
|
pOsdInfo->bandLetter = vtx58BandNames[pOsdInfo->band][0];
|
||||||
|
pOsdInfo->bandName = vtx58BandNames[pOsdInfo->band];
|
||||||
|
pOsdInfo->channelName = vtx58ChannelNames[pOsdInfo->channel];
|
||||||
|
pOsdInfo->powerIndexLetter = '0' + powerIndex;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
static const vtxVTable_t trampVTable = {
|
static const vtxVTable_t trampVTable = {
|
||||||
.process = vtxTrampProcess,
|
.process = vtxTrampProcess,
|
||||||
.getDeviceType = vtxTrampGetDeviceType,
|
.getDeviceType = vtxTrampGetDeviceType,
|
||||||
|
@ -577,11 +593,12 @@ static const vtxVTable_t trampVTable = {
|
||||||
.setBandAndChannel = vtxTrampSetBandAndChannel,
|
.setBandAndChannel = vtxTrampSetBandAndChannel,
|
||||||
.setPowerByIndex = vtxTrampSetPowerByIndex,
|
.setPowerByIndex = vtxTrampSetPowerByIndex,
|
||||||
.setPitMode = vtxTrampSetPitMode,
|
.setPitMode = vtxTrampSetPitMode,
|
||||||
.setFrequency = vtxTrampSetFreq,
|
|
||||||
.getBandAndChannel = vtxTrampGetBandAndChannel,
|
.getBandAndChannel = vtxTrampGetBandAndChannel,
|
||||||
.getPowerIndex = vtxTrampGetPowerIndex,
|
.getPowerIndex = vtxTrampGetPowerIndex,
|
||||||
.getPitMode = vtxTrampGetPitMode,
|
.getPitMode = vtxTrampGetPitMode,
|
||||||
.getFrequency = vtxTrampGetFreq,
|
.getFrequency = vtxTrampGetFreq,
|
||||||
|
.getPower = vtxTrampGetPower,
|
||||||
|
.getOsdInfo = vtxTrampGetOsdInfo,
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -107,9 +107,6 @@
|
||||||
#define SPI3_MISO_PIN PB4
|
#define SPI3_MISO_PIN PB4
|
||||||
#define SPI3_MOSI_PIN PB5
|
#define SPI3_MOSI_PIN PB5
|
||||||
|
|
||||||
#define USE_VTX_RTC6705
|
|
||||||
#define VTX_RTC6705_OPTIONAL // VTX/OSD board is OPTIONAL
|
|
||||||
|
|
||||||
#undef USE_VTX_FFPV
|
#undef USE_VTX_FFPV
|
||||||
#undef USE_VTX_SMARTAUDIO // Disabled due to flash size
|
#undef USE_VTX_SMARTAUDIO // Disabled due to flash size
|
||||||
#undef USE_VTX_TRAMP // Disabled due to flash size
|
#undef USE_VTX_TRAMP // Disabled due to flash size
|
||||||
|
@ -117,19 +114,10 @@
|
||||||
#undef USE_PITOT // Disabled due to RAM size
|
#undef USE_PITOT // Disabled due to RAM size
|
||||||
#undef USE_PITOT_ADC // Disabled due to RAM size
|
#undef USE_PITOT_ADC // Disabled due to RAM size
|
||||||
|
|
||||||
#define RTC6705_CS_PIN PF4
|
|
||||||
#define RTC6705_SPI_INSTANCE SPI3
|
|
||||||
#define RTC6705_POWER_PIN PC3
|
|
||||||
|
|
||||||
#define USE_RTC6705_CLK_HACK
|
|
||||||
#define RTC6705_CLK_PIN SPI3_SCK_PIN
|
|
||||||
|
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
#define MAX7456_SPI_BUS BUS_SPI3
|
#define MAX7456_SPI_BUS BUS_SPI3
|
||||||
#define MAX7456_CS_PIN PA15
|
#define MAX7456_CS_PIN PA15
|
||||||
|
|
||||||
#define SPI_SHARED_MAX7456_AND_RTC6705
|
|
||||||
|
|
||||||
#define USE_SDCARD
|
#define USE_SDCARD
|
||||||
#define USE_SDCARD_SPI
|
#define USE_SDCARD_SPI
|
||||||
#define SDCARD_DETECT_INVERTED
|
#define SDCARD_DETECT_INVERTED
|
||||||
|
|
|
@ -15,5 +15,4 @@ TARGET_SRC = \
|
||||||
drivers/compass/compass_mag3110.c \
|
drivers/compass/compass_mag3110.c \
|
||||||
drivers/compass/compass_lis3mdl.c \
|
drivers/compass/compass_lis3mdl.c \
|
||||||
drivers/light_ws2811strip.c \
|
drivers/light_ws2811strip.c \
|
||||||
drivers/max7456.c \
|
drivers/max7456.c
|
||||||
drivers/vtx_rtc6705.c
|
|
||||||
|
|
|
@ -126,12 +126,6 @@
|
||||||
#define SPI3_MISO_PIN PB4 // NC
|
#define SPI3_MISO_PIN PB4 // NC
|
||||||
#define SPI3_MOSI_PIN PB5 // NC
|
#define SPI3_MOSI_PIN PB5 // NC
|
||||||
|
|
||||||
#define USE_VTX_RTC6705
|
|
||||||
#define VTX_RTC6705_OPTIONAL // SPI3 on an F4 EVO may be used for RTC6705 VTX control.
|
|
||||||
|
|
||||||
#define RTC6705_CS_PIN SPI3_NSS_PIN
|
|
||||||
#define RTC6705_SPI_INSTANCE SPI3
|
|
||||||
|
|
||||||
#define USE_SDCARD
|
#define USE_SDCARD
|
||||||
#define USE_SDCARD_SPI
|
#define USE_SDCARD_SPI
|
||||||
#define SDCARD_DETECT_INVERTED
|
#define SDCARD_DETECT_INVERTED
|
||||||
|
|
|
@ -15,4 +15,3 @@ TARGET_SRC = \
|
||||||
drivers/barometer/barometer_ms56xx.c \
|
drivers/barometer/barometer_ms56xx.c \
|
||||||
drivers/light_ws2811strip.c \
|
drivers/light_ws2811strip.c \
|
||||||
drivers/max7456.c
|
drivers/max7456.c
|
||||||
# drivers/vtx_rtc6705.c
|
|
||||||
|
|
|
@ -155,16 +155,6 @@
|
||||||
#define SDCARD_SPI_BUS BUS_SPI3
|
#define SDCARD_SPI_BUS BUS_SPI3
|
||||||
#define SDCARD_CS_PIN PC3
|
#define SDCARD_CS_PIN PC3
|
||||||
|
|
||||||
// disabled for motor outputs 5-8:
|
|
||||||
//#define USE_VTX_RTC6705
|
|
||||||
//#define USE_VTX_RTC6705_SOFTSPI
|
|
||||||
//#define VTX_RTC6705_OPTIONAL // VTX/OSD board is OPTIONAL
|
|
||||||
|
|
||||||
//#define RTC6705_SPI_MOSI_PIN PB0 // Shared with PWM8
|
|
||||||
//#define RTC6705_CS_PIN PB6 // Shared with PWM5
|
|
||||||
//#define RTC6705_SPICLK_PIN PB1 // Shared with PWM7
|
|
||||||
//#define RTC6705_POWER_PIN PB7 // Shared with PWM6
|
|
||||||
|
|
||||||
#define GYRO_1_CS_PIN SPI1_NSS_PIN
|
#define GYRO_1_CS_PIN SPI1_NSS_PIN
|
||||||
#define GYRO_1_SPI_INSTANCE BUS_SPI1
|
#define GYRO_1_SPI_INSTANCE BUS_SPI1
|
||||||
#define GYRO_2_CS_PIN PB2
|
#define GYRO_2_CS_PIN PB2
|
||||||
|
|
|
@ -15,5 +15,4 @@ TARGET_SRC = \
|
||||||
drivers/compass/compass_mag3110.c \
|
drivers/compass/compass_mag3110.c \
|
||||||
drivers/compass/compass_lis3mdl.c \
|
drivers/compass/compass_lis3mdl.c \
|
||||||
drivers/light_ws2811strip.c \
|
drivers/light_ws2811strip.c \
|
||||||
drivers/max7456.c \
|
drivers/max7456.c
|
||||||
drivers/vtx_rtc6705_soft_spi.c
|
|
|
@ -19,11 +19,6 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
// Targets with built-in vtx do not need external vtx
|
|
||||||
#if defined(VTX) || defined(USE_RTC6705)
|
|
||||||
# undef USE_VTX_CONTROL
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Backward compatibility for I2C OLED display
|
// Backward compatibility for I2C OLED display
|
||||||
#if !defined(USE_I2C)
|
#if !defined(USE_I2C)
|
||||||
# undef USE_DASHBOARD
|
# undef USE_DASHBOARD
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue