mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 00:35:39 +03:00
Minor work
This commit is contained in:
parent
fb518ce37b
commit
10427cb63c
2 changed files with 26 additions and 123 deletions
|
@ -191,7 +191,7 @@ void cmsScreenInit(displayPort_t *pDisp, cmsDeviceInitFuncPtr cmsDeviceInitFunc)
|
|||
//
|
||||
|
||||
#define LEFT_MENU_COLUMN 1
|
||||
#define RIGHT_MENU_COLUMN(p) ((p)->cols - 8)
|
||||
#define RIGHT_MENU_COLUMN(p) ((p)->cols - 10)
|
||||
#define MAX_MENU_ITEMS(p) ((p)->rows - 2)
|
||||
|
||||
displayPort_t currentDisplay;
|
||||
|
@ -873,114 +873,6 @@ void cmsx_InfoInit(void)
|
|||
}
|
||||
}
|
||||
|
||||
#if 0
|
||||
#ifdef VTX_SMARTAUDIO
|
||||
#include "io/vtx_smartaudio.h"
|
||||
|
||||
static const char * const smartAudioBandNames[] = {
|
||||
"--------",
|
||||
"BOSCAM A",
|
||||
"BOSCAM B",
|
||||
"BOSCAM E",
|
||||
"FATSHARK",
|
||||
"RACEBAND",
|
||||
};
|
||||
OSD_TAB_t entrySmartAudioBand = { &smartAudioBand, 5, &smartAudioBandNames[0], NULL };
|
||||
|
||||
static const char * const smartAudioChanNames[] = {
|
||||
"-", "1", "2", "3", "4", "5", "6", "7", "8",
|
||||
};
|
||||
|
||||
OSD_TAB_t entrySmartAudioChan = { &smartAudioChan, 8, &smartAudioChanNames[0], NULL };
|
||||
|
||||
static const char * const smartAudioPowerNames[] = {
|
||||
"---",
|
||||
" 25",
|
||||
"200",
|
||||
"500",
|
||||
"800",
|
||||
};
|
||||
|
||||
OSD_TAB_t entrySmartAudioPower = { &smartAudioPower, 4, &smartAudioPowerNames[0]};
|
||||
|
||||
static const char * const smartAudioTxModeNames[] = {
|
||||
"------",
|
||||
"PIT-OR",
|
||||
"PIT-IR",
|
||||
"ACTIVE",
|
||||
};
|
||||
|
||||
OSD_TAB_t entrySmartAudioTxMode = { &smartAudioTxMode, 3, &smartAudioTxModeNames[0]};
|
||||
|
||||
OSD_UINT16_t entrySmartAudioFreq = { &smartAudioFreq, 5600, 5900, 0 };
|
||||
|
||||
static const char * const smartAudioOpModelNames[] = {
|
||||
"FREE",
|
||||
"PIT",
|
||||
};
|
||||
|
||||
OSD_TAB_t entrySmartAudioOpModel = { &smartAudioOpModel, 1, &smartAudioOpModelNames[0] };
|
||||
|
||||
static const char * const smartAudioPitFModeNames[] = {
|
||||
"IN-RANGE",
|
||||
"OUT-RANGE",
|
||||
};
|
||||
|
||||
OSD_TAB_t entrySmartAudioPitFMode = { &smartAudioPitFMode, 1, &smartAudioPitFModeNames[0] };
|
||||
|
||||
OSD_UINT16_t entrySmartAudioORFreq = { &smartAudioORFreq, 5600, 5900, 1 };
|
||||
|
||||
OSD_Entry menu_smartAudioConfig[] = {
|
||||
{ "--- SMARTAUDIO CONFIG ---", OME_Label, NULL, NULL, 0 },
|
||||
{ "OP MODEL", OME_TAB, smartAudioConfigureOpModelByGvar, &entrySmartAudioOpModel, 0 },
|
||||
{ "PIT FREQ", OME_TAB, smartAudioConfigurePitFModeByGvar, &entrySmartAudioPitFMode, 0 },
|
||||
{ "OR FREQ", OME_UINT16, NULL, &entrySmartAudioORFreq, 0 }, // OME_Poll_UINT16
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
};
|
||||
|
||||
static const char * const smartAudioStatusNames[] = {
|
||||
"OFFLINE",
|
||||
"ONLINE V1",
|
||||
"ONLINE V2",
|
||||
};
|
||||
|
||||
OSD_TAB_t entrySmartAudioOnline = { &smartAudioStatus, 2, &smartAudioStatusNames[0] };
|
||||
OSD_UINT16_t entrySmartAudioBaudrate = { &smartAudioSmartbaud, 0, 0, 0 };
|
||||
OSD_UINT16_t entrySmartAudioStatBadpre = { &saerr_badpre, 0, 0, 0 };
|
||||
OSD_UINT16_t entrySmartAudioStatBadlen = { &saerr_badlen, 0, 0, 0 };
|
||||
OSD_UINT16_t entrySmartAudioStatCrcerr = { &saerr_crcerr, 0, 0, 0 };
|
||||
OSD_UINT16_t entrySmartAudioStatOooerr = { &saerr_oooresp, 0, 0, 0 };
|
||||
|
||||
OSD_Entry menu_smartAudioStats[] = {
|
||||
{ "--- SMARTAUDIO STATS ---", OME_Label, NULL, NULL, 0 },
|
||||
{ "STATUS", OME_TAB, NULL, &entrySmartAudioOnline, 0 },
|
||||
{ "BAUDRATE", OME_UINT16, NULL, &entrySmartAudioBaudrate, 0 },
|
||||
{ "BADPRE", OME_UINT16, NULL, &entrySmartAudioStatBadpre, 0 },
|
||||
{ "BADLEN", OME_UINT16, NULL, &entrySmartAudioStatBadlen, 0 },
|
||||
{ "CRCERR", OME_UINT16, NULL, &entrySmartAudioStatCrcerr, 0 },
|
||||
{ "OOOERR", OME_UINT16, NULL, &entrySmartAudioStatOooerr, 0 },
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
};
|
||||
|
||||
OSD_Entry menu_vtxSmartAudio[] =
|
||||
{
|
||||
{ "-- VTX SMARTAUDIO --", OME_Label, NULL, NULL, 0 },
|
||||
{ smartAudioStatusString, OME_Label, NULL, NULL, 0 },
|
||||
{ "TXMODE", OME_TAB, smartAudioSetTxModeByGvar, &entrySmartAudioTxMode, 0 },
|
||||
{ "BAND", OME_TAB, smartAudioConfigureBandByGvar, &entrySmartAudioBand, 0 },
|
||||
{ "CHAN", OME_TAB, smartAudioConfigureChanByGvar, &entrySmartAudioChan, 0 },
|
||||
{ "FREQ", OME_UINT16, NULL, &entrySmartAudioFreq, 0 },
|
||||
{ "POWER", OME_TAB, smartAudioConfigurePowerByGvar, &entrySmartAudioPower, 0 },
|
||||
{ "CONFIG", OME_Submenu, cmsMenuChange, &menu_smartAudioConfig[0], 0 },
|
||||
{ "STAT", OME_Submenu, cmsMenuChange, &menu_smartAudioStats[0], 0 },
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
};
|
||||
#endif // VTX_SMARTAUDIO
|
||||
#endif // 0
|
||||
|
||||
// Features
|
||||
|
||||
OSD_Entry menuFeatures[] =
|
||||
|
|
|
@ -637,10 +637,11 @@ bool smartAudioInit()
|
|||
return false;
|
||||
}
|
||||
|
||||
smartAudioOpModel = masterConfig.vtx_smartaudio_opmodel;
|
||||
saOpmodel = masterConfig.vtx_smartaudio_opmodel;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void smartAudioProcess(uint32_t now)
|
||||
{
|
||||
static bool initialSent = false;
|
||||
|
@ -689,28 +690,38 @@ void smartAudioProcess(uint32_t now)
|
|||
}
|
||||
|
||||
#ifdef CMS
|
||||
char smartAudioStatusString[31] = "- - ---- --- ---- -";
|
||||
// m bc ffff ppp
|
||||
// 0123456789012
|
||||
char saStatusString[31] = "- -- ---- ---";
|
||||
|
||||
uint8_t saOpmodel = 0;
|
||||
uint8_t smartAudioBand = 0;
|
||||
uint8_t smartAudioChan = 0;
|
||||
uint8_t smartAudioPower = 0;
|
||||
uint16_t smartAudioFreq = 0;
|
||||
|
||||
static void smartAudioUpdateStatusString(void)
|
||||
static void saUpdateStatusString(void)
|
||||
{
|
||||
if (sa_vers == 0)
|
||||
return;
|
||||
|
||||
tfp_sprintf(smartAudioStatusString, "%c %d %4d %3d ",
|
||||
"ABEFR"[sa_chan / 8],
|
||||
(sa_chan % 8) + 1,
|
||||
saFreqTable[sa_chan / 8][sa_chan % 8],
|
||||
(sa_vers == 2) ? saPowerTable[sa_power].rfpower : saPowerTable[saDacToPowerIndex(sa_power)].rfpower);
|
||||
|
||||
if (sa_vers == 2)
|
||||
tfp_sprintf(&smartAudioStatusString[13], "%4d", sa_pitfreq);
|
||||
else
|
||||
tfp_sprintf(&smartAudioStatusString[13], "%4s", "----");
|
||||
saStatusString[0] = "-FP"[saOpmodel];
|
||||
saStatusString[2] = "ABEFR"[sa_chan / 8];
|
||||
saStatusString[3] = '1' + (sa_chan % 8);
|
||||
tfp_sprintf(&smartAudioStatusString[5], "%4d",
|
||||
saFreqTable[sa_chan / 8][sa_chan % 8]);
|
||||
saStatusString[9] = ' ';
|
||||
if (sa_opmode & SA_MODE_GET_PITMODE) {
|
||||
saStatusString[10] = 'P';
|
||||
if (sa_opmode & SA_MODE_GET_IN_RANGE_PITMODE) {
|
||||
saStatusString[10] = 'I';
|
||||
} else {
|
||||
saStatusString[10] = 'O';
|
||||
}
|
||||
saStatusString[11] = 0;
|
||||
} else {
|
||||
tfp_sprintf(&saStatusString[10], "%3d", (sa_vers == 2) ? saPowerTable[sa_power].rfpower : saPowerTable[saDacToPowerIndex(sa_power)].rfpower);
|
||||
}
|
||||
}
|
||||
|
||||
long smartAudioConfigureBandByGvar(displayPort_t *pDisp, void *self)
|
||||
|
@ -938,7 +949,7 @@ OSD_Entry menu_smartAudioStats[] = {
|
|||
|
||||
OSD_Entry cmsx_menuVtxSmartAudio[] =
|
||||
{
|
||||
{ "-- VTX SMARTAUDIO --", OME_Label, NULL, NULL, 0 },
|
||||
{ "- VTX SMARTAUDIO -", OME_Label, NULL, NULL, 0 },
|
||||
{ smartAudioStatusString, OME_Label, NULL, NULL, 0 },
|
||||
{ "TXMODE", OME_TAB, smartAudioSetTxModeByGvar, &entrySmartAudioTxMode, 0 },
|
||||
{ "BAND", OME_TAB, smartAudioConfigureBandByGvar, &entrySmartAudioBand, 0 },
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue