mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-21 15:25:36 +03:00
Fixes and extensions
This commit is contained in:
parent
195d3a3cf3
commit
9bca2b88d0
4 changed files with 41 additions and 87 deletions
|
@ -3,7 +3,7 @@
|
||||||
|
|
||||||
const uint16_t vtx58FreqTable[5][8] =
|
const uint16_t vtx58FreqTable[5][8] =
|
||||||
{
|
{
|
||||||
{ 5865, 5845, 5825, 5805, 5785, 5765, 5745, 5725 }, // Boacam A
|
{ 5865, 5845, 5825, 5805, 5785, 5765, 5745, 5725 }, // Boscam A
|
||||||
{ 5733, 5752, 5771, 5790, 5809, 5828, 5847, 5866 }, // Boscam B
|
{ 5733, 5752, 5771, 5790, 5809, 5828, 5847, 5866 }, // Boscam B
|
||||||
{ 5705, 5685, 5665, 5645, 5885, 5905, 5925, 5945 }, // Boscam E
|
{ 5705, 5685, 5665, 5645, 5885, 5905, 5925, 5945 }, // Boscam E
|
||||||
{ 5740, 5760, 5780, 5800, 5820, 5840, 5860, 5880 }, // FatShark
|
{ 5740, 5760, 5780, 5800, 5820, 5840, 5860, 5880 }, // FatShark
|
||||||
|
|
|
@ -1,37 +1,3 @@
|
||||||
|
#pragma once
|
||||||
struct vtxVTable_s;
|
|
||||||
typedef struct vtxDevice_s {
|
|
||||||
const struct vtxVTable_s *vTable;
|
|
||||||
uint8_t numBand;
|
|
||||||
uint8_t numChan;
|
|
||||||
uint8_t numPower;
|
|
||||||
|
|
||||||
uint16_t *freqTable;
|
|
||||||
|
|
||||||
// Config variable?
|
|
||||||
uint8_t opModel; // Power up in: 0 = transmitting, 1 = pit mode
|
|
||||||
|
|
||||||
// CMS only?
|
|
||||||
uint8_t curBand;
|
|
||||||
uint8_t curChan;
|
|
||||||
uint8_t curPower;
|
|
||||||
uint8_t curPitState; // 0 = PIT, 1 = non-PIT
|
|
||||||
|
|
||||||
// CMS only?
|
|
||||||
char *bandNames;
|
|
||||||
char *chanNames;
|
|
||||||
char *powerNames;
|
|
||||||
} vtxDevice_t;
|
|
||||||
|
|
||||||
typedef struct vtxVTable_s {
|
|
||||||
void (*setBandChan)(uint8_t band, uint8_t chan);
|
|
||||||
void (*setFreq)(uint16_t freq);
|
|
||||||
void (*setRFPower)(uint8_t level); // 0 = OFF, 1~ = device dep.
|
|
||||||
void (*setPitmode)(uint8_t onoff);
|
|
||||||
} vtxVTable_t;
|
|
||||||
|
|
||||||
// PIT mode is defined as LOWEST POSSIBLE RF POWER.
|
|
||||||
// - It can be a dedicated mode, or lowest RF power possible.
|
|
||||||
// - It is *NOT* RF on/off control.
|
|
||||||
|
|
||||||
bool vtx58_Freq2Bandchan(uint16_t freq, uint8_t *pBand, uint8_t *pChan);
|
bool vtx58_Freq2Bandchan(uint16_t freq, uint8_t *pBand, uint8_t *pChan);
|
||||||
|
|
|
@ -33,6 +33,7 @@
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
|
#include "drivers/vtx_var.h"
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "io/vtx_smartaudio.h"
|
#include "io/vtx_smartaudio.h"
|
||||||
|
|
||||||
|
@ -130,18 +131,6 @@ static smartAudioStat_t saStat = {
|
||||||
.badcode = 0,
|
.badcode = 0,
|
||||||
};
|
};
|
||||||
|
|
||||||
// The band/chan to frequency table
|
|
||||||
// XXX Should really be consolidated among different vtx drivers
|
|
||||||
static const uint16_t saFreqTable[5][8] =
|
|
||||||
{
|
|
||||||
{ 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
|
|
||||||
};
|
|
||||||
// XXX Should frequencies not usable in locked state be detected?
|
|
||||||
|
|
||||||
typedef struct saPowerTable_s {
|
typedef struct saPowerTable_s {
|
||||||
int rfpower;
|
int rfpower;
|
||||||
int16_t valueV1;
|
int16_t valueV1;
|
||||||
|
@ -767,9 +756,9 @@ void saCmsUpdate(void)
|
||||||
|
|
||||||
saCmsBand = (saDevice.chan / 8) + 1;
|
saCmsBand = (saDevice.chan / 8) + 1;
|
||||||
saCmsChan = (saDevice.chan % 8) + 1;
|
saCmsChan = (saDevice.chan % 8) + 1;
|
||||||
saCmsFreqRef = saFreqTable[saDevice.chan / 8][saDevice.chan % 8];
|
saCmsFreqRef = vtx58FreqTable[saDevice.chan / 8][saDevice.chan % 8];
|
||||||
|
|
||||||
saCmsDeviceFreq = saFreqTable[saDevice.chan / 8][saDevice.chan % 8];
|
saCmsDeviceFreq = vtx58FreqTable[saDevice.chan / 8][saDevice.chan % 8];
|
||||||
|
|
||||||
if ((saDevice.mode & SA_MODE_GET_PITMODE) == 0) {
|
if ((saDevice.mode & SA_MODE_GET_PITMODE) == 0) {
|
||||||
saCmsRFState = SACMS_TXMODE_ACTIVE;
|
saCmsRFState = SACMS_TXMODE_ACTIVE;
|
||||||
|
@ -828,7 +817,7 @@ else
|
||||||
tfp_sprintf(&saCmsStatusString[5], "%4d", saDevice.freq);
|
tfp_sprintf(&saCmsStatusString[5], "%4d", saDevice.freq);
|
||||||
else
|
else
|
||||||
tfp_sprintf(&saCmsStatusString[5], "%4d",
|
tfp_sprintf(&saCmsStatusString[5], "%4d",
|
||||||
saFreqTable[saDevice.chan / 8][saDevice.chan % 8]);
|
vtx58FreqTable[saDevice.chan / 8][saDevice.chan % 8]);
|
||||||
|
|
||||||
saCmsStatusString[9] = ' ';
|
saCmsStatusString[9] = ' ';
|
||||||
|
|
||||||
|
@ -868,7 +857,7 @@ dprintf(("saCmsConfigBand: band req %d ", saCmsBand));
|
||||||
if (!(saCmsOpmodel == SACMS_OPMODEL_FREE && saDeferred))
|
if (!(saCmsOpmodel == SACMS_OPMODEL_FREE && saDeferred))
|
||||||
saSetBandChan(saCmsBand - 1, saCmsChan - 1);
|
saSetBandChan(saCmsBand - 1, saCmsChan - 1);
|
||||||
|
|
||||||
saCmsFreqRef = saFreqTable[saCmsBand - 1][saCmsChan - 1];
|
saCmsFreqRef = vtx58FreqTable[saCmsBand - 1][saCmsChan - 1];
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
@ -893,7 +882,7 @@ static long saCmsConfigChanByGvar(displayPort_t *pDisp, const void *self)
|
||||||
if (!(saCmsOpmodel == SACMS_OPMODEL_FREE && saDeferred))
|
if (!(saCmsOpmodel == SACMS_OPMODEL_FREE && saDeferred))
|
||||||
saSetBandChan(saCmsBand - 1, saCmsChan - 1);
|
saSetBandChan(saCmsBand - 1, saCmsChan - 1);
|
||||||
|
|
||||||
saCmsFreqRef = saFreqTable[saCmsBand - 1][saCmsChan - 1];
|
saCmsFreqRef = vtx58FreqTable[saCmsBand - 1][saCmsChan - 1];
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
@ -994,22 +983,9 @@ static CMS_Menu saCmsMenuStats = {
|
||||||
.entries = saCmsMenuStatsEntries
|
.entries = saCmsMenuStatsEntries
|
||||||
};
|
};
|
||||||
|
|
||||||
static const char * const saCmsBandNames[] = {
|
static OSD_TAB_t saCmsEntBand = { &saCmsBand, 5, vtx58BandNames, NULL };
|
||||||
"--------",
|
|
||||||
"BOSCAM A",
|
|
||||||
"BOSCAM B",
|
|
||||||
"BOSCAM E",
|
|
||||||
"FATSHARK",
|
|
||||||
"RACEBAND",
|
|
||||||
};
|
|
||||||
|
|
||||||
static OSD_TAB_t saCmsEntBand = { &saCmsBand, 5, &saCmsBandNames[0], NULL };
|
static OSD_TAB_t saCmsEntChan = { &saCmsChan, 8, &vtx58ChanNames[0], NULL };
|
||||||
|
|
||||||
static const char * const saCmsChanNames[] = {
|
|
||||||
"-", "1", "2", "3", "4", "5", "6", "7", "8",
|
|
||||||
};
|
|
||||||
|
|
||||||
static OSD_TAB_t saCmsEntChan = { &saCmsChan, 8, &saCmsChanNames[0], NULL };
|
|
||||||
|
|
||||||
static const char * const saCmsPowerNames[] = {
|
static const char * const saCmsPowerNames[] = {
|
||||||
"---",
|
"---",
|
||||||
|
|
|
@ -57,7 +57,9 @@ uint32_t trampRFPowerMax;
|
||||||
uint32_t trampCurFreq = 0;
|
uint32_t trampCurFreq = 0;
|
||||||
uint8_t trampCurBand = 0;
|
uint8_t trampCurBand = 0;
|
||||||
uint8_t trampCurChan = 0;
|
uint8_t trampCurChan = 0;
|
||||||
uint16_t trampCurPower = 0;
|
uint16_t trampCurPower = 0; // Actual transmitting power
|
||||||
|
uint16_t trampCurConfigPower = 0; // Configured transmitting power
|
||||||
|
int16_t trampCurTemp = 0;
|
||||||
|
|
||||||
#ifdef CMS
|
#ifdef CMS
|
||||||
void trampCmsUpdateStatusString(void); // Forward
|
void trampCmsUpdateStatusString(void); // Forward
|
||||||
|
@ -167,10 +169,13 @@ void trampHandleResponse(void)
|
||||||
|
|
||||||
case 'v':
|
case 'v':
|
||||||
trampCurFreq = trampRespBuffer[2]|(trampRespBuffer[3] << 8);
|
trampCurFreq = trampRespBuffer[2]|(trampRespBuffer[3] << 8);
|
||||||
|
trampCurConfigPower = trampRespBuffer[4]|(trampRespBuffer[5] << 8);
|
||||||
|
trampCurPower = trampRespBuffer[8]|(trampRespBuffer[9] << 8);
|
||||||
vtx58_Freq2Bandchan(trampCurFreq, &trampCurBand, &trampCurChan);
|
vtx58_Freq2Bandchan(trampCurFreq, &trampCurBand, &trampCurChan);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 's':
|
case 's':
|
||||||
|
trampCurTemp = (int16_t)(trampRespBuffer[6]|(trampRespBuffer[7] << 8));
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -207,7 +212,7 @@ void trampReceive(uint32_t currentTimeUs)
|
||||||
if (!trampSerialPort)
|
if (!trampSerialPort)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
if ((trampReceiveState != S_WAIT_LEN) && (currentTimeUs - trampFrameStartUs > TRAMP_FRAME_TIMO_US)) {
|
if ((trampReceiveState != S_WAIT_LEN) && cmp32(currentTimeUs, trampFrameStartUs > TRAMP_FRAME_TIMO_US)) {
|
||||||
trampReceiveState = S_WAIT_LEN;
|
trampReceiveState = S_WAIT_LEN;
|
||||||
trampReceivePos = 0;
|
trampReceivePos = 0;
|
||||||
}
|
}
|
||||||
|
@ -216,7 +221,7 @@ void trampReceive(uint32_t currentTimeUs)
|
||||||
uint8_t c = serialRead(trampSerialPort);
|
uint8_t c = serialRead(trampSerialPort);
|
||||||
trampRespBuffer[trampReceivePos++] = c;
|
trampRespBuffer[trampReceivePos++] = c;
|
||||||
|
|
||||||
switch(c) {
|
switch(trampReceiveState) {
|
||||||
case S_WAIT_LEN:
|
case S_WAIT_LEN:
|
||||||
if (c == 0x0F) {
|
if (c == 0x0F) {
|
||||||
trampReceiveState = S_WAIT_CODE;
|
trampReceiveState = S_WAIT_CODE;
|
||||||
|
@ -254,17 +259,17 @@ void trampProcess(uint32_t currentTimeUs)
|
||||||
if (trampStatus == TRAMP_STATUS_BAD_DEVICE)
|
if (trampStatus == TRAMP_STATUS_BAD_DEVICE)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
debug[0]++;
|
|
||||||
trampReceive(currentTimeUs);
|
trampReceive(currentTimeUs);
|
||||||
|
|
||||||
if (trampStatus == TRAMP_STATUS_OFFLINE) {
|
if (trampStatus == TRAMP_STATUS_OFFLINE) {
|
||||||
if (currentTimeUs - lastQueryRTimeUs > 1000 * 1000) {
|
if (cmp32(currentTimeUs, lastQueryRTimeUs) > 1000 * 1000) {
|
||||||
trampQueryR();
|
trampQueryR();
|
||||||
lastQueryRTimeUs = currentTimeUs;
|
lastQueryRTimeUs = currentTimeUs;
|
||||||
}
|
}
|
||||||
} else if (trampPendingQuery) {
|
} else if (trampReceiveState == S_WAIT_LEN) {
|
||||||
|
if (trampPendingQuery)
|
||||||
trampQuery(trampPendingQuery);
|
trampQuery(trampPendingQuery);
|
||||||
} else {
|
else
|
||||||
trampQueryV();
|
trampQueryV();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -277,25 +282,29 @@ debug[0]++;
|
||||||
#include "cms/cms.h"
|
#include "cms/cms.h"
|
||||||
#include "cms/cms_types.h"
|
#include "cms/cms_types.h"
|
||||||
|
|
||||||
char trampCmsStatusString[16];
|
|
||||||
|
char trampCmsStatusString[31] = "- -- ---- ----";
|
||||||
|
// m bc ffff tppp
|
||||||
|
// 01234567890123
|
||||||
|
|
||||||
void trampCmsUpdateStatusString(void)
|
void trampCmsUpdateStatusString(void)
|
||||||
{
|
{
|
||||||
trampCmsStatusString[0] = '*';
|
trampCmsStatusString[0] = '*';
|
||||||
trampCmsStatusString[1] = ' ';
|
trampCmsStatusString[1] = ' ';
|
||||||
trampCmsStatusString[3] = vtx58BandLetter[trampCurBand];
|
trampCmsStatusString[2] = vtx58BandLetter[trampCurBand];
|
||||||
trampCmsStatusString[4] = vtx58ChanNames[trampCurChan][0];
|
trampCmsStatusString[3] = vtx58ChanNames[trampCurChan][0];
|
||||||
trampCmsStatusString[5] = ' ';
|
trampCmsStatusString[4] = ' ';
|
||||||
|
|
||||||
if (trampCurFreq)
|
if (trampCurFreq)
|
||||||
tfp_sprintf(&trampCmsStatusString[6], "%4d", trampCurFreq);
|
tfp_sprintf(&trampCmsStatusString[5], "%4d", trampCurFreq);
|
||||||
else
|
else
|
||||||
tfp_sprintf(&trampCmsStatusString[6], "----");
|
tfp_sprintf(&trampCmsStatusString[5], "----");
|
||||||
|
|
||||||
if (trampCurPower)
|
if (trampCurPower) {
|
||||||
tfp_sprintf(&trampCmsStatusString[10], " %3d", trampCurPower);
|
tfp_sprintf(&trampCmsStatusString[9], " %c%3d", (trampCurPower == trampCurConfigPower) ? ' ' : '*', trampCurPower);
|
||||||
|
}
|
||||||
else
|
else
|
||||||
tfp_sprintf(&trampCmsStatusString[10], " ---");
|
tfp_sprintf(&trampCmsStatusString[9], " ---");
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t trampCmsPitmode = 0;
|
uint8_t trampCmsPitmode = 0;
|
||||||
|
@ -319,7 +328,9 @@ static const uint16_t trampCmsPowerTable[] = {
|
||||||
|
|
||||||
static uint8_t trampCmsPower = 0;
|
static uint8_t trampCmsPower = 0;
|
||||||
|
|
||||||
static OSD_TAB_t trampCmsEntPower = { &trampCmsPower, 5, trampCmsPowerNames, NULL };
|
static OSD_TAB_t trampCmsEntPower = { &trampCmsPower, 4, trampCmsPowerNames, NULL };
|
||||||
|
|
||||||
|
static OSD_INT16_t trampCmsEntTemp = { &trampCurTemp, -100, 300, 0 };
|
||||||
|
|
||||||
static const char * const trampCmsPitmodeNames[] = {
|
static const char * const trampCmsPitmodeNames[] = {
|
||||||
"OFF", "ON "
|
"OFF", "ON "
|
||||||
|
@ -379,6 +390,7 @@ static OSD_Entry trampMenuEntries[] =
|
||||||
{ "CHAN", OME_TAB, NULL, &trampCmsEntChan, 0 },
|
{ "CHAN", OME_TAB, NULL, &trampCmsEntChan, 0 },
|
||||||
{ "(FREQ)", OME_UINT16, NULL, &trampCmsEntFreqRef, DYNAMIC },
|
{ "(FREQ)", OME_UINT16, NULL, &trampCmsEntFreqRef, DYNAMIC },
|
||||||
{ "POWER", OME_TAB, NULL, &trampCmsEntPower, 0 },
|
{ "POWER", OME_TAB, NULL, &trampCmsEntPower, 0 },
|
||||||
|
{ "TEMP", OME_INT16, NULL, &trampCmsEntTemp, DYNAMIC },
|
||||||
{ "SET", OME_Submenu, cmsMenuChange, &trampCmsMenuCommence, 0 },
|
{ "SET", OME_Submenu, cmsMenuChange, &trampCmsMenuCommence, 0 },
|
||||||
//{ "CONFIG", OME_Submenu, cmsMenuChange, &saCmsMenuConfig, 0 },
|
//{ "CONFIG", OME_Submenu, cmsMenuChange, &saCmsMenuConfig, 0 },
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue