save not set for vtx OSD settings
[betaflight.git] / src / main / cms / cms_menu_vtx_smartaudio.c
blob36147097447f76636286378bc0ef82f6ca7d7831
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
21 #include <stdbool.h>
22 #include <stdint.h>
23 #include <ctype.h>
24 #include <string.h>
25 #include <drivers/vtx_table.h>
27 #include "platform.h"
29 #if defined(USE_CMS) && defined(USE_VTX_SMARTAUDIO)
31 #include "common/printf.h"
32 #include "common/utils.h"
34 #include "cms/cms.h"
35 #include "cms/cms_types.h"
36 #include "cms/cms_menu_vtx_smartaudio.h"
38 #include "drivers/vtx_common.h"
40 #include "config/config.h"
42 #include "io/vtx_smartaudio.h"
43 #include "io/vtx.h"
45 // Interface to CMS
47 // Operational Model and RF modes (CMS)
49 #define SACMS_OPMODEL_UNDEF 0 // Not known yet
50 #define SACMS_OPMODEL_FREE 1 // Freestyle model: Power up transmitting
51 #define SACMS_OPMODEL_RACE 2 // Race model: Power up in pit mode
53 uint8_t saCmsOpmodel = SACMS_OPMODEL_UNDEF;
55 #define SACMS_TXMODE_NODEF 0
56 #define SACMS_TXMODE_PIT_OUTRANGE 1
57 #define SACMS_TXMODE_PIT_INRANGE 2
58 #define SACMS_TXMODE_ACTIVE 3
60 uint8_t saCmsRFState; // RF state; ACTIVE, PIR, POR XXX Not currently used
62 uint8_t saCmsBand = 0;
63 uint8_t saCmsChan = 0;
64 uint8_t saCmsPower = 0;
66 // Frequency derived from channel table (used for reference in band/channel mode)
67 uint16_t saCmsFreqRef = 0;
69 uint16_t saCmsDeviceFreq = 0;
71 uint8_t saCmsDeviceStatus = 0;
72 uint8_t saCmsPower;
73 uint8_t saCmsPit;
74 uint8_t saCmsPitFMode; // Undef(0), In-Range(1) or Out-Range(2)
76 uint8_t saCmsFselMode; // Channel(0) or User defined(1)
77 uint8_t saCmsFselModeNew; // Channel(0) or User defined(1)
79 uint16_t saCmsORFreq = 0; // POR frequency
80 uint16_t saCmsORFreqNew; // POR frequency
82 uint16_t saCmsUserFreq = 0; // User defined frequency
83 uint16_t saCmsUserFreqNew; // User defined frequency
85 void saCmsUpdate(void)
87 // XXX Take care of pit mode update somewhere???
88 if (saCmsOpmodel == SACMS_OPMODEL_UNDEF) {
89 // This is a first valid response to GET_SETTINGS.
90 saCmsOpmodel = saDevice.willBootIntoPitMode ? SACMS_OPMODEL_RACE : SACMS_OPMODEL_FREE;
92 saCmsFselMode = (saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ) && vtxSettingsConfig()->band == 0 ? 1 : 0;
94 saCmsBand = vtxSettingsConfig()->band;
95 saCmsChan = vtxSettingsConfig()->channel;
96 saCmsFreqRef = vtxSettingsConfig()->freq;
97 saCmsDeviceFreq = saCmsFreqRef;
99 if ((saDevice.mode & SA_MODE_GET_PITMODE) == 0) {
100 saCmsRFState = SACMS_TXMODE_ACTIVE;
101 } else if (saDevice.mode & SA_MODE_GET_IN_RANGE_PITMODE) {
102 saCmsRFState = SACMS_TXMODE_PIT_INRANGE;
103 } else {
104 saCmsRFState = SACMS_TXMODE_PIT_OUTRANGE;
107 saCmsPower = vtxSettingsConfig()->power;
109 // if user-freq mode then track possible change
110 if (saCmsFselMode && vtxSettingsConfig()->freq) {
111 saCmsUserFreq = vtxSettingsConfig()->freq;
114 saCmsFselModeNew = saCmsFselMode; //init mode for menu
117 saUpdateStatusString();
120 char saCmsStatusString[31] = "- -- ---- ---";
121 // m bc ffff ppp
122 // 0123456789012
124 static const void *saCmsConfigOpmodelByGvar(displayPort_t *, const void *self);
125 static const void *saCmsConfigPitFModeByGvar(displayPort_t *, const void *self);
126 static const void *saCmsConfigBandByGvar(displayPort_t *, const void *self);
127 static const void *saCmsConfigChanByGvar(displayPort_t *, const void *self);
128 static const void *saCmsConfigPowerByGvar(displayPort_t *, const void *self);
129 static const void *saCmsConfigPitByGvar(displayPort_t *, const void *self);
131 void saUpdateStatusString(void)
133 if (saDevice.version == 0)
134 return;
136 // XXX These should be done somewhere else
137 if (saCmsDeviceStatus == 0 && saDevice.version != 0)
138 saCmsDeviceStatus = saDevice.version;
139 if (saCmsORFreq == 0 && saDevice.orfreq != 0)
140 saCmsORFreq = saDevice.orfreq;
141 if (saCmsUserFreq == 0 && saDevice.freq != 0)
142 saCmsUserFreq = saDevice.freq;
144 if (saDevice.version == 2) {
145 if (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE)
146 saCmsPitFMode = 1;
147 else
148 saCmsPitFMode = 0;
149 } else if (saDevice.version == 3) {
150 saCmsPitFMode = 1;//V2.1 only supports PIR
153 const vtxDevice_t *device = vtxCommonDevice();
155 saCmsStatusString[0] = "-FR"[saCmsOpmodel];
157 if (saCmsFselMode == 0) {
158 uint8_t band;
159 uint8_t channel;
160 vtxCommonGetBandAndChannel(device, &band, &channel);
161 saCmsStatusString[2] = vtxCommonLookupBandLetter(device, band);
162 saCmsStatusString[3] = vtxCommonLookupChannelName(device, channel)[0];
163 } else {
164 saCmsStatusString[2] = 'U';
165 saCmsStatusString[3] = 'F';
168 if ((saDevice.mode & SA_MODE_GET_PITMODE)
169 && (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE)) {
170 tfp_sprintf(&saCmsStatusString[5], "%4d", saDevice.orfreq);
171 } else {
172 uint16_t freq = 0;
173 vtxCommonGetFrequency(device, &freq);
174 tfp_sprintf(&saCmsStatusString[5], "%4d", freq);
177 saCmsStatusString[9] = ' ';
179 if (saDevice.mode & SA_MODE_GET_PITMODE) {
180 saCmsPit = 2;
181 saCmsStatusString[10] = 'P';
182 if (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE) {
183 saCmsStatusString[11] = 'O';
184 } else {
185 saCmsStatusString[11] = 'I';
187 saCmsStatusString[12] = 'R';
188 saCmsStatusString[13] = 0;
189 } else {
190 saCmsPit = 1;
191 uint8_t powerIndex = 0;
192 bool powerFound = vtxCommonGetPowerIndex(device, &powerIndex);
193 tfp_sprintf(&saCmsStatusString[10], "%s", powerFound ? vtxCommonLookupPowerName(device, powerIndex) : "???");
196 if (vtxTableBandCount == 0 || vtxTablePowerLevels == 0) {
197 strncpy(saCmsStatusString, "PLEASE CONFIGURE VTXTABLE", sizeof(saCmsStatusString));
201 void saCmsResetOpmodel()
203 // trigger data refresh in 'saCmsUpdate()'
204 saCmsOpmodel = SACMS_OPMODEL_UNDEF;
207 static const void *saCmsConfigBandByGvar(displayPort_t *pDisp, const void *self)
209 UNUSED(pDisp);
210 UNUSED(self);
212 if (saDevice.version == 0) {
213 // Bounce back; not online yet
214 saCmsBand = 0;
215 return NULL;
218 if (saCmsBand == 0) {
219 // Bouce back, no going back to undef state
220 saCmsBand = 1;
221 return NULL;
224 if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred) {
225 vtxCommonSetBandAndChannel(vtxCommonDevice(), saCmsBand, saCmsChan);
228 saCmsFreqRef = vtxCommonLookupFrequency(vtxCommonDevice(), saCmsBand, saCmsChan);
230 return NULL;
233 static const void *saCmsConfigChanByGvar(displayPort_t *pDisp, const void *self)
235 UNUSED(pDisp);
236 UNUSED(self);
238 if (saDevice.version == 0) {
239 // Bounce back; not online yet
240 saCmsChan = 0;
241 return NULL;
244 if (saCmsChan == 0) {
245 // Bounce back; no going back to undef state
246 saCmsChan = 1;
247 return NULL;
250 if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred) {
251 vtxCommonSetBandAndChannel(vtxCommonDevice(), saCmsBand, saCmsChan);
254 saCmsFreqRef = vtxCommonLookupFrequency(vtxCommonDevice(), saCmsBand, saCmsChan);
256 return NULL;
259 static const void *saCmsConfigPitByGvar(displayPort_t *pDisp, const void *self)
261 UNUSED(pDisp);
262 UNUSED(self);
264 dprintf(("saCmsConfigPitByGvar: saCmsPit %d\r\n", saCmsPit));
266 if (saDevice.version == 0) {
267 // Bounce back; not online yet
268 saCmsPit = 0;
269 return NULL;
272 if (saCmsPit == 0) {//trying to go back to undef state; bounce back
273 saCmsPit = 1;
274 return NULL;
276 if (saDevice.power != saCmsPower) {//we can't change both power and pit mode at once
277 saCmsPower = saDevice.power;
280 return NULL;
283 static const void *saCmsConfigPowerByGvar(displayPort_t *pDisp, const void *self)
285 UNUSED(pDisp);
286 UNUSED(self);
288 if (saDevice.version == 0) {
289 // Bounce back; not online yet
290 saCmsPower = 0;
291 return NULL;
294 if (saCmsPower == 0) {
295 // Bouce back; no going back to undef state
296 saCmsPower = 1;
297 return NULL;
300 if (saCmsPit > 0 && saCmsPit != 1 ) {
301 saCmsPit = 1;
304 if (saCmsOpmodel == SACMS_OPMODEL_FREE && !saDeferred) {
305 vtxSettingsConfigMutable()->power = saCmsPower;
307 dprintf(("saCmsConfigPowerByGvar: power index is now %d\r\n", saCmsPower));
309 return NULL;
312 static const void *saCmsConfigPitFModeByGvar(displayPort_t *pDisp, const void *self)
314 UNUSED(pDisp);
315 UNUSED(self);
317 if (saDevice.version == 1) {
318 // V1 device doesn't support PIT mode; bounce back.
319 saCmsPitFMode = 0;
320 return NULL;
322 if (saDevice.version >= 3) {
323 // V2.1 device only supports PIR mode. and setting any flag immediately enables pit mode.
324 //therefore: bounce back.
325 saCmsPitFMode = 1;
326 return NULL;
329 dprintf(("saCmsConfigPitFmodeByGbar: saCmsPitFMode %d\r\n", saCmsPitFMode));
331 if (saCmsPitFMode == 0) {
332 // Bounce back
333 saCmsPitFMode = 1;
334 return NULL;
337 if (saCmsPitFMode == 1) {
338 saSetMode(SA_MODE_SET_IN_RANGE_PITMODE);
339 } else {
340 saSetMode(SA_MODE_SET_OUT_RANGE_PITMODE);
343 return NULL;
346 static const void *saCmsConfigFreqModeByGvar(displayPort_t *pDisp, const void *self); // Forward
348 static const void *saCmsConfigOpmodelByGvar(displayPort_t *pDisp, const void *self)
350 UNUSED(pDisp);
351 UNUSED(self);
353 if (saDevice.version == 1) {
354 if (saCmsOpmodel != SACMS_OPMODEL_FREE)
355 saCmsOpmodel = SACMS_OPMODEL_FREE;
356 return NULL;
359 uint8_t opmodel = saCmsOpmodel;
361 dprintf(("saCmsConfigOpmodelByGvar: opmodel %d\r\n", opmodel));
363 if (opmodel == SACMS_OPMODEL_FREE) {
364 // VTX should power up transmitting.
365 // Turn off In-Range and Out-Range bits
366 saSetMode(0);
367 } else if (opmodel == SACMS_OPMODEL_RACE) {
368 // VTX should power up in pit mode.
369 // Default PitFMode is in-range to prevent users without
370 // out-range receivers from getting blinded.
371 saCmsPitFMode = 0;
372 saCmsConfigPitFModeByGvar(pDisp, self);
373 if (saDevice.version >= 3) {
374 saSetMode(SA_MODE_SET_IN_RANGE_PITMODE | ((saDevice.mode & SA_MODE_GET_PITMODE) ? 0 : SA_MODE_CLR_PITMODE));
377 // Direct frequency mode is not available in RACE opmodel
378 saCmsFselModeNew = 0;
379 saCmsConfigFreqModeByGvar(pDisp, self);
380 } else {
381 // Trying to go back to unknown state; bounce back
382 saCmsOpmodel = SACMS_OPMODEL_UNDEF + 1;
385 return NULL;
388 #ifdef USE_EXTENDED_CMS_MENUS
389 static const char * const saCmsDeviceStatusNames[] = {
390 "OFFL",
391 "ONL V1",
392 "ONL V2",
393 "ONLV21",
396 static OSD_TAB_t saCmsEntOnline = { &saCmsDeviceStatus, 3, saCmsDeviceStatusNames };
398 static const OSD_Entry saCmsMenuStatsEntries[] = {
399 { "- SA STATS -", OME_Label, NULL, NULL },
400 { "STATUS", OME_TAB | DYNAMIC, NULL, &saCmsEntOnline },
401 { "BAUDRATE", OME_UINT16 | DYNAMIC, NULL, &(OSD_UINT16_t){ &sa_smartbaud, 0, 0, 0 } },
402 { "SENT", OME_UINT16 | DYNAMIC, NULL, &(OSD_UINT16_t){ &saStat.pktsent, 0, 0, 0 } },
403 { "RCVD", OME_UINT16 | DYNAMIC, NULL, &(OSD_UINT16_t){ &saStat.pktrcvd, 0, 0, 0 } },
404 { "BADPRE", OME_UINT16 | DYNAMIC, NULL, &(OSD_UINT16_t){ &saStat.badpre, 0, 0, 0 } },
405 { "BADLEN", OME_UINT16 | DYNAMIC, NULL, &(OSD_UINT16_t){ &saStat.badlen, 0, 0, 0 } },
406 { "CRCERR", OME_UINT16 | DYNAMIC, NULL, &(OSD_UINT16_t){ &saStat.crc, 0, 0, 0 } },
407 { "OOOERR", OME_UINT16 | DYNAMIC, NULL, &(OSD_UINT16_t){ &saStat.ooopresp, 0, 0, 0 } },
408 { "BACK", OME_Back, NULL, NULL },
409 { NULL, OME_END, NULL, NULL }
412 static CMS_Menu saCmsMenuStats = {
413 #ifdef CMS_MENU_DEBUG
414 .GUARD_text = "XSAST",
415 .GUARD_type = OME_MENU,
416 #endif
417 .onEnter = NULL,
418 .onExit = NULL,
419 .onDisplayUpdate = NULL,
420 .entries = saCmsMenuStatsEntries
422 #endif /* USE_EXTENDED_CMS_MENUS */
424 static OSD_TAB_t saCmsEntBand;
425 static OSD_TAB_t saCmsEntChan;
426 static OSD_TAB_t saCmsEntPower;
428 static void saCmsInitNames(void)
430 saCmsEntBand.val = &saCmsBand;
431 saCmsEntBand.max = vtxTableBandCount;
432 saCmsEntBand.names = vtxTableBandNames;
434 saCmsEntChan.val = &saCmsChan;
435 saCmsEntChan.max = vtxTableChannelCount;
436 saCmsEntChan.names = vtxTableChannelNames;
438 saCmsEntPower.val = &saCmsPower;
439 saCmsEntPower.max = vtxTablePowerLevels;
440 saCmsEntPower.names = vtxTablePowerLabels;
443 static OSD_UINT16_t saCmsEntFreqRef = { &saCmsFreqRef, 5600, 5900, 0 };
445 static const char * const saCmsOpmodelNames[] = {
446 "----",
447 "FREE",
448 "RACE",
451 static const char * const saCmsFselModeNames[] = {
452 "CHAN",
453 "USER"
456 static const char * const saCmsPitFModeNames[] = {
457 "---",
458 "PIR",
459 "POR"
462 static const char * const saCmsPitNames[] = {
463 "---",
464 "OFF",
465 "ON ",
468 static OSD_TAB_t saCmsEntPitFMode = { &saCmsPitFMode, 1, saCmsPitFModeNames };
469 static OSD_TAB_t saCmsEntPit = {&saCmsPit, 2, saCmsPitNames};
471 static const void *sacms_SetupTopMenu(displayPort_t *pDisp); // Forward
473 static const void *saCmsConfigFreqModeByGvar(displayPort_t *pDisp, const void *self)
475 UNUSED(pDisp);
476 UNUSED(self);
478 // if trying to do user frequency mode in RACE opmodel then
479 // revert because user-freq only available in FREE opmodel
480 if (saCmsFselModeNew != 0 && saCmsOpmodel != SACMS_OPMODEL_FREE) {
481 saCmsFselModeNew = 0;
484 // don't call 'saSetBandAndChannel()' / 'saSetFreq()' here,
485 // wait until SET / 'saCmsCommence()' is activated
487 sacms_SetupTopMenu(pDisp);
489 return NULL;
492 static const void *saCmsCommence(displayPort_t *pDisp, const void *self)
494 UNUSED(pDisp);
495 UNUSED(self);
497 const vtxSettingsConfig_t prevSettings = {
498 .band = vtxSettingsConfig()->band,
499 .channel = vtxSettingsConfig()->channel,
500 .freq = vtxSettingsConfig()->freq,
501 .power = vtxSettingsConfig()->power,
502 .lowPowerDisarm = vtxSettingsConfig()->lowPowerDisarm,
504 vtxSettingsConfig_t newSettings = prevSettings;
506 if (saCmsOpmodel == SACMS_OPMODEL_RACE) {
507 // Race model
508 // Setup band, freq and power.
510 newSettings.band = saCmsBand;
511 newSettings.channel = saCmsChan;
512 newSettings.freq = vtxCommonLookupFrequency(vtxCommonDevice(), saCmsBand, saCmsChan);
513 } else {
514 // Freestyle model
515 // Setup band and freq / user freq
516 if (saCmsFselModeNew == 0) {
517 newSettings.band = saCmsBand;
518 newSettings.channel = saCmsChan;
519 newSettings.freq = vtxCommonLookupFrequency(vtxCommonDevice(), saCmsBand, saCmsChan);
520 } else {
521 saSetMode(0); //make sure FREE mode is setup
522 newSettings.band = 0;
523 newSettings.freq = saCmsUserFreq;
527 if (newSettings.power == saCmsPower && saCmsPit > 0) {
528 vtxCommonSetPitMode(vtxCommonDevice(), saCmsPit == 2);
530 newSettings.power = saCmsPower;
532 if (memcmp(&prevSettings, &newSettings, sizeof(vtxSettingsConfig_t))) {
533 vtxSettingsConfigMutable()->band = newSettings.band;
534 vtxSettingsConfigMutable()->channel = newSettings.channel;
535 vtxSettingsConfigMutable()->power = newSettings.power;
536 vtxSettingsConfigMutable()->freq = newSettings.freq;
537 saveConfigAndNotify();
540 return MENU_CHAIN_BACK;
543 static const void *saCmsSetPORFreqOnEnter(displayPort_t *pDisp)
545 UNUSED(pDisp);
547 if (saDevice.version == 1)
548 return MENU_CHAIN_BACK;
550 saCmsORFreqNew = saCmsORFreq;
552 return NULL;
555 static const void *saCmsSetPORFreq(displayPort_t *pDisp, const void *self)
557 UNUSED(pDisp);
558 UNUSED(self);
560 saSetPitFreq(saCmsORFreqNew);
562 return NULL;
565 static const char *saCmsORFreqGetString(displayPort_t *pDisp, const void *self)
567 UNUSED(pDisp);
568 UNUSED(self);
570 static char pbuf[5];
572 tfp_sprintf(pbuf, "%4d", saCmsORFreq);
574 return pbuf;
577 static const char *saCmsUserFreqGetString(displayPort_t *pDisp, const void *self)
579 UNUSED(pDisp);
580 UNUSED(self);
582 static char pbuf[5];
584 tfp_sprintf(pbuf, "%4d", saCmsUserFreq);
586 return pbuf;
589 static const void *saCmsSetUserFreqOnEnter(displayPort_t *pDisp)
591 UNUSED(pDisp);
593 saCmsUserFreqNew = saCmsUserFreq;
595 return NULL;
598 static const void *saCmsConfigUserFreq(displayPort_t *pDisp, const void *self)
600 UNUSED(pDisp);
601 UNUSED(self);
603 saCmsUserFreq = saCmsUserFreqNew;
605 return MENU_CHAIN_BACK;
608 static const OSD_Entry saCmsMenuPORFreqEntries[] = {
609 { "- POR FREQ -", OME_Label, NULL, NULL },
611 { "CUR FREQ", OME_UINT16 | DYNAMIC, NULL, &(OSD_UINT16_t){ &saCmsORFreq, 5000, 5999, 0 } },
612 { "NEW FREQ", OME_UINT16, NULL, &(OSD_UINT16_t){ &saCmsORFreqNew, 5000, 5999, 1 } },
613 { "SAVE", OME_Funcall, saCmsSetPORFreq, NULL },
615 { "BACK", OME_Back, NULL, NULL },
616 { NULL, OME_END, NULL, NULL }
619 static CMS_Menu saCmsMenuPORFreq =
621 #ifdef CMS_MENU_DEBUG
622 .GUARD_text = "XSAPOR",
623 .GUARD_type = OME_MENU,
624 #endif
625 .onEnter = saCmsSetPORFreqOnEnter,
626 .onExit = NULL,
627 .onDisplayUpdate = NULL,
628 .entries = saCmsMenuPORFreqEntries,
631 static const OSD_Entry saCmsMenuUserFreqEntries[] = {
632 { "- USER FREQ -", OME_Label, NULL, NULL },
634 { "CUR FREQ", OME_UINT16 | DYNAMIC, NULL, &(OSD_UINT16_t){ &saCmsUserFreq, 5000, 5999, 0 } },
635 { "NEW FREQ", OME_UINT16, NULL, &(OSD_UINT16_t){ &saCmsUserFreqNew, 5000, 5999, 1 } },
636 { "SAVE", OME_Funcall, saCmsConfigUserFreq, NULL },
638 { "BACK", OME_Back, NULL, NULL },
639 { NULL, OME_END, NULL, NULL }
642 static CMS_Menu saCmsMenuUserFreq =
644 #ifdef CMS_MENU_DEBUG
645 .GUARD_text = "XSAUFQ",
646 .GUARD_type = OME_MENU,
647 #endif
648 .onEnter = saCmsSetUserFreqOnEnter,
649 .onExit = NULL,
650 .onDisplayUpdate = NULL,
651 .entries = saCmsMenuUserFreqEntries,
654 static OSD_TAB_t saCmsEntFselMode = { &saCmsFselModeNew, 1, saCmsFselModeNames };
656 static const OSD_Entry saCmsMenuConfigEntries[] = {
657 { "- SA CONFIG -", OME_Label, NULL, NULL },
659 { "OP MODEL", OME_TAB | DYNAMIC, saCmsConfigOpmodelByGvar, &(OSD_TAB_t){ &saCmsOpmodel, 2, saCmsOpmodelNames } },
660 { "FSEL MODE", OME_TAB | DYNAMIC, saCmsConfigFreqModeByGvar, &saCmsEntFselMode },
661 { "PIT FMODE", OME_TAB, saCmsConfigPitFModeByGvar, &saCmsEntPitFMode },
662 { "POR FREQ", OME_Submenu | OPTSTRING, (CMSEntryFuncPtr)saCmsORFreqGetString, &saCmsMenuPORFreq },
663 #ifdef USE_EXTENDED_CMS_MENUS
664 { "STATX", OME_Submenu, cmsMenuChange, &saCmsMenuStats },
665 #endif /* USE_EXTENDED_CMS_MENUS */
667 { "BACK", OME_Back, NULL, NULL },
668 { NULL, OME_END, NULL, NULL}
671 static CMS_Menu saCmsMenuConfig = {
672 #ifdef CMS_MENU_DEBUG
673 .GUARD_text = "XSACFG",
674 .GUARD_type = OME_MENU,
675 #endif
676 .onEnter = NULL,
677 .onExit = NULL,
678 .onDisplayUpdate = NULL,
679 .entries = saCmsMenuConfigEntries
682 static const OSD_Entry saCmsMenuCommenceEntries[] = {
683 { "CONFIRM", OME_Label, NULL, NULL },
685 { "YES", OME_Funcall, saCmsCommence, NULL },
687 { "NO", OME_Back, NULL, NULL },
688 { NULL, OME_END, NULL, NULL }
691 static CMS_Menu saCmsMenuCommence = {
692 #ifdef CMS_MENU_DEBUG
693 .GUARD_text = "XVTXCOM",
694 .GUARD_type = OME_MENU,
695 #endif
696 .onEnter = NULL,
697 .onExit = NULL,
698 .onDisplayUpdate = NULL,
699 .entries = saCmsMenuCommenceEntries,
702 static const OSD_Entry saCmsMenuFreqModeEntries[] = {
703 { "- SMARTAUDIO -", OME_Label, NULL, NULL },
705 { "", OME_Label | DYNAMIC, NULL, saCmsStatusString },
706 { "FREQ", OME_Submenu | OPTSTRING, (CMSEntryFuncPtr)saCmsUserFreqGetString, &saCmsMenuUserFreq },
707 { "POWER", OME_TAB | DYNAMIC, saCmsConfigPowerByGvar, &saCmsEntPower },
708 { "PIT", OME_TAB | DYNAMIC, saCmsConfigPitByGvar, &saCmsEntPit },
709 { "SAVE", OME_Submenu, cmsMenuChange, &saCmsMenuCommence },
710 { "CONFIG", OME_Submenu, cmsMenuChange, &saCmsMenuConfig },
712 { "BACK", OME_Back, NULL, NULL },
713 { NULL, OME_END, NULL, NULL}
716 static const OSD_Entry saCmsMenuChanModeEntries[] =
718 { "- SMARTAUDIO -", OME_Label, NULL, NULL },
720 { "", OME_Label | DYNAMIC, NULL, saCmsStatusString },
721 { "BAND", OME_TAB, saCmsConfigBandByGvar, &saCmsEntBand },
722 { "CHAN", OME_TAB, saCmsConfigChanByGvar, &saCmsEntChan },
723 { "(FREQ)", OME_UINT16 | DYNAMIC, NULL, &saCmsEntFreqRef },
724 { "POWER", OME_TAB | DYNAMIC, saCmsConfigPowerByGvar, &saCmsEntPower },
725 { "PIT", OME_TAB | DYNAMIC, saCmsConfigPitByGvar, &saCmsEntPit },
726 { "SAVE", OME_Submenu, cmsMenuChange, &saCmsMenuCommence },
727 { "CONFIG", OME_Submenu, cmsMenuChange, &saCmsMenuConfig },
729 { "BACK", OME_Back, NULL, NULL },
730 { NULL, OME_END, NULL, NULL }
733 static const OSD_Entry saCmsMenuOfflineEntries[] =
735 { "- VTX SMARTAUDIO -", OME_Label, NULL, NULL },
737 { "", OME_Label | DYNAMIC, NULL, saCmsStatusString },
738 #ifdef USE_EXTENDED_CMS_MENUS
739 { "STATX", OME_Submenu, cmsMenuChange, &saCmsMenuStats },
740 #endif /* USE_EXTENDED_CMS_MENUS */
742 { "BACK", OME_Back, NULL, NULL },
743 { NULL, OME_END, NULL, NULL }
746 CMS_Menu cmsx_menuVtxSmartAudio; // Forward
748 static const void *sacms_SetupTopMenu(displayPort_t *pDisp)
750 UNUSED(pDisp);
752 if (saCmsDeviceStatus) {
753 if (saCmsFselModeNew == 0)
754 cmsx_menuVtxSmartAudio.entries = saCmsMenuChanModeEntries;
755 else
756 cmsx_menuVtxSmartAudio.entries = saCmsMenuFreqModeEntries;
757 } else {
758 cmsx_menuVtxSmartAudio.entries = saCmsMenuOfflineEntries;
761 saCmsInitNames();
763 return NULL;
766 CMS_Menu cmsx_menuVtxSmartAudio = {
767 #ifdef CMS_MENU_DEBUG
768 .GUARD_text = "XVTXSA",
769 .GUARD_type = OME_MENU,
770 #endif
771 .onEnter = sacms_SetupTopMenu,
772 .onExit = NULL,
773 .onDisplayUpdate = NULL,
774 .entries = saCmsMenuOfflineEntries,
777 #endif // CMS