mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-22 15:55:48 +03:00
Make CMS fields readonly when overridden by a slider and mark with an S
This commit is contained in:
parent
adcc36888b
commit
3de0d384ed
20 changed files with 564 additions and 521 deletions
|
@ -50,6 +50,7 @@
|
|||
|
||||
#include "config/config.h"
|
||||
#include "config/feature.h"
|
||||
#include "config/simplified_tuning.h"
|
||||
|
||||
#include "drivers/motor.h"
|
||||
#include "drivers/osd_symbols.h"
|
||||
|
@ -72,6 +73,8 @@
|
|||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
// DisplayPort management
|
||||
|
||||
#ifndef CMS_MAX_DEVICE
|
||||
|
@ -192,10 +195,10 @@ static bool saveMenuInhibited = false;
|
|||
static char menuErrLabel[21 + 1] = "RANDOM DATA";
|
||||
|
||||
static OSD_Entry menuErrEntries[] = {
|
||||
{ "BROKEN MENU", OME_Label, NULL, NULL, 0 },
|
||||
{ menuErrLabel, OME_Label, NULL, NULL, 0 },
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BROKEN MENU", OME_Label, NULL, NULL },
|
||||
{ menuErrLabel, OME_Label, NULL, NULL },
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
static CMS_Menu menuErr = {
|
||||
|
@ -221,7 +224,7 @@ static void cmsUpdateMaxRow(displayPort_t *instance)
|
|||
UNUSED(instance);
|
||||
pageMaxRow = 0;
|
||||
|
||||
for (const OSD_Entry *ptr = pageTop; ptr->type != OME_END; ptr++) {
|
||||
for (const OSD_Entry *ptr = pageTop; (ptr->flags & OSD_MENU_ELEMENT_MASK) != OME_END; ptr++) {
|
||||
pageMaxRow++;
|
||||
}
|
||||
|
||||
|
@ -408,7 +411,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t
|
|||
row++;
|
||||
}
|
||||
|
||||
switch (p->type) {
|
||||
switch (p->flags & OSD_MENU_ELEMENT_MASK) {
|
||||
case OME_String:
|
||||
if (IS_PRINTVALUE(*flags) && p->data) {
|
||||
strncpy(buff, p->data, CMS_DRAW_BUFFER_LEN);
|
||||
|
@ -422,13 +425,13 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t
|
|||
if (IS_PRINTVALUE(*flags)) {
|
||||
buff[0]= 0x0;
|
||||
|
||||
if (p->type == OME_Submenu && p->func && *flags & OPTSTRING) {
|
||||
if ((p->flags & OSD_MENU_ELEMENT_MASK) == OME_Submenu && p->func && *flags & OPTSTRING) {
|
||||
|
||||
// Special case of sub menu entry with optional value display.
|
||||
|
||||
const char *str = p->func(pDisplay, p->data);
|
||||
strncpy(buff, str, CMS_DRAW_BUFFER_LEN);
|
||||
} else if (p->type == OME_Funcall && p->data) {
|
||||
} else if ((p->flags & OSD_MENU_ELEMENT_MASK) == OME_Funcall && p->data) {
|
||||
strncpy(buff, p->data, CMS_DRAW_BUFFER_LEN);
|
||||
}
|
||||
strncat(buff, ">", CMS_DRAW_BUFFER_LEN);
|
||||
|
@ -617,7 +620,7 @@ static void cmsMenuCountPage(displayPort_t *pDisplay)
|
|||
{
|
||||
UNUSED(pDisplay);
|
||||
const OSD_Entry *p;
|
||||
for (p = currentCtx.menu->entries; p->type != OME_END; p++);
|
||||
for (p = currentCtx.menu->entries; (p->flags & OSD_MENU_ELEMENT_MASK) != OME_END; p++);
|
||||
pageCount = (p - currentCtx.menu->entries - 1) / maxMenuItems + 1;
|
||||
}
|
||||
|
||||
|
@ -649,18 +652,47 @@ STATIC_UNIT_TESTED const void *cmsMenuBack(displayPort_t *pDisplay)
|
|||
return NULL;
|
||||
}
|
||||
|
||||
// Check if overridden by slider
|
||||
static bool rowSliderOverride(const uint16_t flags)
|
||||
{
|
||||
#ifdef UNIT_TEST
|
||||
UNUSED(flags);
|
||||
#else
|
||||
pidSimplifiedTuningMode_e simplified_pids_mode = currentPidProfile->simplified_pids_mode;
|
||||
|
||||
bool slider_flags_mode_rpy = (simplified_pids_mode == PID_SIMPLIFIED_TUNING_RPY);
|
||||
bool slider_flags_mode_rp = slider_flags_mode_rpy || (simplified_pids_mode == PID_SIMPLIFIED_TUNING_RP);
|
||||
|
||||
bool simplified_gyro_filter = gyroConfig()->simplified_gyro_filter;
|
||||
bool simplified_dterm_filter = currentPidProfile->simplified_dterm_filter;
|
||||
|
||||
if (((flags & SLIDER_RP) && slider_flags_mode_rp) ||
|
||||
((flags & SLIDER_RPY) && slider_flags_mode_rpy) ||
|
||||
((flags & SLIDER_GYRO) && simplified_gyro_filter) ||
|
||||
((flags & SLIDER_DTERM) && simplified_dterm_filter)) {
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
// Skip read-only entries
|
||||
static bool rowIsSkippable(const OSD_Entry *row)
|
||||
{
|
||||
if (row->type == OME_Label) {
|
||||
OSD_MenuElement type = row->flags & OSD_MENU_ELEMENT_MASK;
|
||||
|
||||
if (type == OME_Label) {
|
||||
return true;
|
||||
}
|
||||
|
||||
if (row->type == OME_String) {
|
||||
if (type == OME_String) {
|
||||
return true;
|
||||
}
|
||||
|
||||
if ((row->type == OME_UINT16 || row->type == OME_INT16) && row->flags == DYNAMIC) {
|
||||
if ((type == OME_UINT8 || type == OME_INT8 ||
|
||||
type == OME_UINT16 || type == OME_INT16) &&
|
||||
((row->flags == DYNAMIC) || rowSliderOverride(row->flags))) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
|
@ -743,7 +775,7 @@ static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs)
|
|||
for (i = 0, p = pageTop; (p <= pageTop + pageMaxRow); i++, p++) {
|
||||
if (IS_PRINTLABEL(runtimeEntryFlags[i])) {
|
||||
uint8_t coloff = leftMenuColumn;
|
||||
coloff += (p->type == OME_Label) ? 0 : 1;
|
||||
coloff += ((p->flags & OSD_MENU_ELEMENT_MASK) == OME_Label) ? 0 : 1;
|
||||
room -= cmsDisplayWrite(pDisplay, coloff, top + i * linesPerMenuItem, DISPLAYPORT_ATTR_NONE, p->text);
|
||||
CLR_PRINTLABEL(runtimeEntryFlags[i]);
|
||||
if (room < 30) {
|
||||
|
@ -751,6 +783,12 @@ static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs)
|
|||
}
|
||||
}
|
||||
|
||||
|
||||
// Highlight values overridden by sliders
|
||||
if (rowSliderOverride(p->flags)) {
|
||||
displayWriteChar(pDisplay, leftMenuColumn - 1, top + i * linesPerMenuItem, DISPLAYPORT_ATTR_NONE, 'S');
|
||||
}
|
||||
|
||||
// Print values
|
||||
|
||||
// XXX Polled values at latter positions in the list may not be
|
||||
|
@ -913,8 +951,8 @@ void cmsMenuOpen(void)
|
|||
|
||||
static void cmsTraverseGlobalExit(const CMS_Menu *pMenu)
|
||||
{
|
||||
for (const OSD_Entry *p = pMenu->entries; p->type != OME_END ; p++) {
|
||||
if (p->type == OME_Submenu) {
|
||||
for (const OSD_Entry *p = pMenu->entries; (p->flags & OSD_MENU_ELEMENT_MASK) != OME_END ; p++) {
|
||||
if ((p->flags & OSD_MENU_ELEMENT_MASK) == OME_Submenu) {
|
||||
cmsTraverseGlobalExit(p->data);
|
||||
}
|
||||
}
|
||||
|
@ -1033,7 +1071,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, cms_key_e key)
|
|||
while ((rowIsSkippable(pageTop + currentCtx.cursorRow)) && currentCtx.cursorRow > 0) {
|
||||
currentCtx.cursorRow--;
|
||||
}
|
||||
if (currentCtx.cursorRow == -1 || (pageTop + currentCtx.cursorRow)->type == OME_Label) {
|
||||
if (currentCtx.cursorRow == -1 || ((pageTop + currentCtx.cursorRow)->flags & OSD_MENU_ELEMENT_MASK) == OME_Label) {
|
||||
// Goto previous page
|
||||
cmsPagePrev(pDisplay);
|
||||
currentCtx.cursorRow = pageMaxRow;
|
||||
|
@ -1046,7 +1084,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, cms_key_e key)
|
|||
|
||||
p = pageTop + currentCtx.cursorRow;
|
||||
|
||||
switch (p->type) {
|
||||
switch (p->flags & OSD_MENU_ELEMENT_MASK) {
|
||||
case OME_Submenu:
|
||||
if (key == CMS_KEY_RIGHT) {
|
||||
cmsMenuChange(pDisplay, p->data);
|
||||
|
@ -1157,7 +1195,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, cms_key_e key)
|
|||
break;
|
||||
|
||||
case OME_TAB:
|
||||
if (p->type == OME_TAB) {
|
||||
if ((p->flags & OSD_MENU_ELEMENT_MASK) == OME_TAB) {
|
||||
OSD_TAB_t *ptr = p->data;
|
||||
const uint8_t previousValue = *ptr->val;
|
||||
|
||||
|
@ -1467,13 +1505,12 @@ void inhibitSaveMenu(void)
|
|||
saveMenuInhibited = true;
|
||||
}
|
||||
|
||||
void cmsAddMenuEntry(OSD_Entry *menuEntry, char *text, OSD_MenuElement type, CMSEntryFuncPtr func, void *data, uint8_t flags)
|
||||
void cmsAddMenuEntry(OSD_Entry *menuEntry, char *text, uint16_t flags, CMSEntryFuncPtr func, void *data)
|
||||
{
|
||||
menuEntry->text = text;
|
||||
menuEntry->type = type;
|
||||
menuEntry->flags = flags;
|
||||
menuEntry->func = func;
|
||||
menuEntry->data = data;
|
||||
menuEntry->flags = flags;
|
||||
}
|
||||
|
||||
#endif // CMS
|
||||
|
|
|
@ -54,7 +54,7 @@ const void *cmsMenuChange(displayPort_t *pPort, const void *ptr);
|
|||
const void *cmsMenuExit(displayPort_t *pPort, const void *ptr);
|
||||
void cmsSetExternKey(cms_key_e extKey);
|
||||
void inhibitSaveMenu(void);
|
||||
void cmsAddMenuEntry(OSD_Entry *menuEntry, char *text, OSD_MenuElement type, CMSEntryFuncPtr func, void *data, uint8_t flags);
|
||||
void cmsAddMenuEntry(OSD_Entry *menuEntry, char *text, uint16_t flags, CMSEntryFuncPtr func, void *data);
|
||||
|
||||
#define CMS_STARTUP_HELP_TEXT1 "MENU:THR MID"
|
||||
#define CMS_STARTUP_HELP_TEXT2 "+ YAW LEFT"
|
||||
|
|
|
@ -226,11 +226,11 @@ static const void *cmsx_Blackbox_onExit(displayPort_t *pDisp, const OSD_Entry *s
|
|||
// Check before erase flash
|
||||
#ifdef USE_FLASHFS
|
||||
static const OSD_Entry menuEraseFlashCheckEntries[] = {
|
||||
{ "CONFIRM ERASE", OME_Label, NULL, NULL, 0},
|
||||
{ "YES", OME_Funcall, cmsx_EraseFlash, NULL, 0 },
|
||||
{ "CONFIRM ERASE", OME_Label, NULL, NULL},
|
||||
{ "YES", OME_Funcall, cmsx_EraseFlash, NULL },
|
||||
|
||||
{ "NO", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "NO", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL }
|
||||
};
|
||||
|
||||
static CMS_Menu cmsx_menuEraseFlashCheck = {
|
||||
|
@ -247,21 +247,21 @@ static CMS_Menu cmsx_menuEraseFlashCheck = {
|
|||
|
||||
static const OSD_Entry cmsx_menuBlackboxEntries[] =
|
||||
{
|
||||
{ "-- BLACKBOX --", OME_Label, NULL, NULL, 0},
|
||||
{ "(PID FREQ)", OME_String, NULL, &cmsx_pidFreq, 0 },
|
||||
{ "SAMPLERATE", OME_TAB, NULL, &cmsx_BlackboxRateTable, REBOOT_REQUIRED },
|
||||
{ "DEVICE", OME_TAB, NULL, &cmsx_BlackboxDeviceTable, REBOOT_REQUIRED },
|
||||
{ "(STATUS)", OME_String, NULL, &cmsx_BlackboxStatus, 0 },
|
||||
{ "(USED)", OME_String, NULL, &cmsx_BlackboxDeviceStorageUsed, 0 },
|
||||
{ "(FREE)", OME_String, NULL, &cmsx_BlackboxDeviceStorageFree, 0 },
|
||||
{ "DEBUG MODE", OME_TAB, NULL, &(OSD_TAB_t) { &systemConfig_debug_mode, DEBUG_COUNT - 1, debugModeNames }, REBOOT_REQUIRED },
|
||||
{ "-- BLACKBOX --", OME_Label, NULL, NULL},
|
||||
{ "(PID FREQ)", OME_String, NULL, &cmsx_pidFreq },
|
||||
{ "SAMPLERATE", OME_TAB | REBOOT_REQUIRED, NULL, &cmsx_BlackboxRateTable },
|
||||
{ "DEVICE", OME_TAB | REBOOT_REQUIRED, NULL, &cmsx_BlackboxDeviceTable },
|
||||
{ "(STATUS)", OME_String, NULL, &cmsx_BlackboxStatus },
|
||||
{ "(USED)", OME_String, NULL, &cmsx_BlackboxDeviceStorageUsed },
|
||||
{ "(FREE)", OME_String, NULL, &cmsx_BlackboxDeviceStorageFree },
|
||||
{ "DEBUG MODE", OME_TAB | REBOOT_REQUIRED, NULL, &(OSD_TAB_t) { &systemConfig_debug_mode, DEBUG_COUNT - 1, debugModeNames } },
|
||||
|
||||
#ifdef USE_FLASHFS
|
||||
{ "ERASE FLASH", OME_Submenu, cmsMenuChange, &cmsx_menuEraseFlashCheck, 0 },
|
||||
{ "ERASE FLASH", OME_Submenu, cmsMenuChange, &cmsx_menuEraseFlashCheck },
|
||||
#endif // USE_FLASHFS
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
CMS_Menu cmsx_menuBlackbox = {
|
||||
|
|
|
@ -75,17 +75,17 @@ static const void *cmsx_Failsafe_onExit(displayPort_t *pDisp, const OSD_Entry *s
|
|||
|
||||
static const OSD_Entry cmsx_menuFailsafeEntries[] =
|
||||
{
|
||||
{ "-- FAILSAFE --", OME_Label, NULL, NULL, 0},
|
||||
{ "-- FAILSAFE --", OME_Label, NULL, NULL},
|
||||
|
||||
{ "PROCEDURE", OME_TAB, NULL, &(OSD_TAB_t) { &failsafeConfig_failsafe_procedure, FAILSAFE_PROCEDURE_COUNT - 1, failsafeProcedureNames }, REBOOT_REQUIRED },
|
||||
{ "GUARD TIME", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &failsafeConfig_failsafe_delay, 0, 200, 1, 100 }, REBOOT_REQUIRED },
|
||||
{ "STAGE 2 DELAY", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &failsafeConfig_failsafe_off_delay, 0, 200, 1, 100 }, REBOOT_REQUIRED },
|
||||
{ "STAGE 2 THROTTLE", OME_UINT16, NULL, &(OSD_UINT16_t) { &failsafeConfig_failsafe_throttle, PWM_PULSE_MIN, PWM_PULSE_MAX, 1 }, REBOOT_REQUIRED },
|
||||
{ "PROCEDURE", OME_TAB | REBOOT_REQUIRED, NULL, &(OSD_TAB_t) { &failsafeConfig_failsafe_procedure, FAILSAFE_PROCEDURE_COUNT - 1, failsafeProcedureNames } },
|
||||
{ "GUARD TIME", OME_FLOAT | REBOOT_REQUIRED, NULL, &(OSD_FLOAT_t) { &failsafeConfig_failsafe_delay, 0, 200, 1, 100 } },
|
||||
{ "STAGE 2 DELAY", OME_FLOAT | REBOOT_REQUIRED, NULL, &(OSD_FLOAT_t) { &failsafeConfig_failsafe_off_delay, 0, 200, 1, 100 } },
|
||||
{ "STAGE 2 THROTTLE", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t) { &failsafeConfig_failsafe_throttle, PWM_PULSE_MIN, PWM_PULSE_MAX, 1 } },
|
||||
#ifdef USE_CMS_GPS_RESCUE_MENU
|
||||
{ "GPS RESCUE", OME_Submenu, cmsMenuChange, &cmsx_menuGpsRescue, 0},
|
||||
{ "GPS RESCUE", OME_Submenu, cmsMenuChange, &cmsx_menuGpsRescue},
|
||||
#endif
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
CMS_Menu cmsx_menuFailsafe = {
|
||||
|
|
|
@ -129,13 +129,13 @@ static const void *cmsCalibrateBaro(displayPort_t *pDisp, const void *self)
|
|||
|
||||
#if defined(USE_ACC)
|
||||
static const OSD_Entry menuCalibrateAccEntries[] = {
|
||||
{ "--- CALIBRATE ACC ---", OME_Label, NULL, NULL, 0 },
|
||||
{ "PLACE ON A LEVEL SURFACE", OME_Label, NULL, NULL, 0},
|
||||
{ "MAKE SURE CRAFT IS STILL", OME_Label, NULL, NULL, 0},
|
||||
{ " ", OME_Label, NULL, NULL, 0},
|
||||
{ "START CALIBRATION", OME_Funcall, cmsCalibrateAcc, NULL, 0 },
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "--- CALIBRATE ACC ---", OME_Label, NULL, NULL },
|
||||
{ "PLACE ON A LEVEL SURFACE", OME_Label, NULL, NULL},
|
||||
{ "MAKE SURE CRAFT IS STILL", OME_Label, NULL, NULL},
|
||||
{ " ", OME_Label, NULL, NULL},
|
||||
{ "START CALIBRATION", OME_Funcall, cmsCalibrateAcc, NULL },
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
CMS_Menu cmsx_menuCalibrateAcc = {
|
||||
|
@ -163,16 +163,16 @@ const void *cmsCalibrateAccMenu(displayPort_t *pDisp, const void *self)
|
|||
#endif
|
||||
|
||||
static const OSD_Entry menuCalibrationEntries[] = {
|
||||
{ "--- CALIBRATE ---", OME_Label, NULL, NULL, 0 },
|
||||
{ "GYRO", OME_Funcall, cmsCalibrateGyro, gyroCalibrationStatus, DYNAMIC },
|
||||
{ "--- CALIBRATE ---", OME_Label, NULL, NULL },
|
||||
{ "GYRO", OME_Funcall | DYNAMIC, cmsCalibrateGyro, gyroCalibrationStatus },
|
||||
#if defined(USE_ACC)
|
||||
{ "ACC", OME_Funcall, cmsCalibrateAccMenu, accCalibrationStatus, DYNAMIC },
|
||||
{ "ACC", OME_Funcall | DYNAMIC, cmsCalibrateAccMenu, accCalibrationStatus },
|
||||
#endif
|
||||
#if defined(USE_BARO)
|
||||
{ "BARO", OME_Funcall, cmsCalibrateBaro, baroCalibrationStatus, DYNAMIC },
|
||||
{ "BARO", OME_Funcall | DYNAMIC, cmsCalibrateBaro, baroCalibrationStatus },
|
||||
#endif
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
static CMS_Menu cmsx_menuCalibration = {
|
||||
|
@ -204,19 +204,19 @@ static const void *cmsx_FirmwareInit(displayPort_t *pDisp)
|
|||
#endif
|
||||
|
||||
static const OSD_Entry menuFirmwareEntries[] = {
|
||||
{ "--- INFO ---", OME_Label, NULL, NULL, 0 },
|
||||
{ "FWID", OME_String, NULL, FC_FIRMWARE_IDENTIFIER, 0 },
|
||||
{ "FWVER", OME_String, NULL, FC_VERSION_STRING, 0 },
|
||||
{ "GITREV", OME_String, NULL, __REVISION__, 0 },
|
||||
{ "TARGET", OME_String, NULL, __TARGET__, 0 },
|
||||
{ "--- INFO ---", OME_Label, NULL, NULL },
|
||||
{ "FWID", OME_String, NULL, FC_FIRMWARE_IDENTIFIER },
|
||||
{ "FWVER", OME_String, NULL, FC_VERSION_STRING },
|
||||
{ "GITREV", OME_String, NULL, __REVISION__ },
|
||||
{ "TARGET", OME_String, NULL, __TARGET__ },
|
||||
#if defined(USE_BOARD_INFO)
|
||||
{ "MFR", OME_String, NULL, manufacturerId, 0 },
|
||||
{ "BOARD", OME_String, NULL, boardName, 0 },
|
||||
{ "MFR", OME_String, NULL, manufacturerId },
|
||||
{ "BOARD", OME_String, NULL, boardName },
|
||||
#endif
|
||||
{ "--- SETUP ---", OME_Label, NULL, NULL, 0 },
|
||||
{ "CALIBRATE", OME_Submenu, cmsMenuChange, &cmsx_menuCalibration, 0},
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "--- SETUP ---", OME_Label, NULL, NULL },
|
||||
{ "CALIBRATE", OME_Submenu, cmsMenuChange, &cmsx_menuCalibration},
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
CMS_Menu cmsx_menuFirmware = {
|
||||
|
|
|
@ -96,20 +96,20 @@ static const void *cms_menuGpsRescuePidOnExit(displayPort_t *pDisp, const OSD_En
|
|||
|
||||
const OSD_Entry cms_menuGpsRescuePidEntries[] =
|
||||
{
|
||||
{"--- GPS RESCUE PID---", OME_Label, NULL, NULL, 0},
|
||||
{"--- GPS RESCUE PID---", OME_Label, NULL, NULL},
|
||||
|
||||
{ "THROTTLE P", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleP, 0, 500, 1 }, REBOOT_REQUIRED },
|
||||
{ "THROTTLE I", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleI, 0, 500, 1 }, REBOOT_REQUIRED },
|
||||
{ "THROTTLE D", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleD, 0, 500, 1 }, REBOOT_REQUIRED },
|
||||
{ "THROTTLE P", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleP, 0, 500, 1 } },
|
||||
{ "THROTTLE I", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleI, 0, 500, 1 } },
|
||||
{ "THROTTLE D", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleD, 0, 500, 1 } },
|
||||
|
||||
{ "YAW P", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_yawP, 0, 500, 1 }, REBOOT_REQUIRED },
|
||||
{ "YAW P", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_yawP, 0, 500, 1 } },
|
||||
|
||||
{ "VELOCITY P", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_velP, 0, 500, 1 }, REBOOT_REQUIRED },
|
||||
{ "VELOCITY I", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_velI, 0, 500, 1 }, REBOOT_REQUIRED },
|
||||
{ "VELOCITY D", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_velD, 0, 500, 1 }, REBOOT_REQUIRED },
|
||||
{ "VELOCITY P", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_velP, 0, 500, 1 } },
|
||||
{ "VELOCITY I", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_velI, 0, 500, 1 } },
|
||||
{ "VELOCITY D", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_velD, 0, 500, 1 } },
|
||||
|
||||
{"BACK", OME_Back, NULL, NULL, 0},
|
||||
{NULL, OME_END, NULL, NULL, 0}
|
||||
{"BACK", OME_Back, NULL, NULL},
|
||||
{NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
CMS_Menu cms_menuGpsRescuePid = {
|
||||
|
@ -172,27 +172,27 @@ static const void *cmsx_menuGpsRescueOnExit(displayPort_t *pDisp, const OSD_Entr
|
|||
|
||||
const OSD_Entry cmsx_menuGpsRescueEntries[] =
|
||||
{
|
||||
{"--- GPS RESCUE ---", OME_Label, NULL, NULL, 0},
|
||||
{"--- GPS RESCUE ---", OME_Label, NULL, NULL},
|
||||
|
||||
{ "ANGLE", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_angle, 0, 200 ,1 }, REBOOT_REQUIRED },
|
||||
{ "MIN DIST HOME M", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_minRescueDth, 50, 1000 ,1 }, REBOOT_REQUIRED },
|
||||
{ "INITAL ALT M", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_initialAltitudeM, 20, 100, 1 }, REBOOT_REQUIRED },
|
||||
{ "ALTITUDE MODE" , OME_TAB, NULL, &(OSD_TAB_t) { &gpsRescueConfig_altitudeMode, 2, lookupTableRescueAltitudeMode}, REBOOT_REQUIRED },
|
||||
{ "DESCENT DIST M", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_descentDistanceM, 30, 500, 1 }, REBOOT_REQUIRED },
|
||||
{ "LANDING ALT M", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_targetLandingAltitudeM, 3, 10, 1 }, REBOOT_REQUIRED },
|
||||
{ "LANDING DIST M", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_targetLandingDistanceM, 5, 15, 1 }, REBOOT_REQUIRED },
|
||||
{ "GROUND SPEED CM/S", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_rescueGroundspeed, 30, 3000, 1 }, REBOOT_REQUIRED },
|
||||
{ "THROTTLE MIN", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleMin, 1000, 2000, 1 }, REBOOT_REQUIRED },
|
||||
{ "THROTTLE MAX", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleMax, 1000, 2000, 1 }, REBOOT_REQUIRED },
|
||||
{ "THROTTLE HOV", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleHover, 1000, 2000, 1 }, REBOOT_REQUIRED },
|
||||
{ "ASCEND RATE", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_ascendRate, 100, 2500, 1 }, REBOOT_REQUIRED },
|
||||
{ "DESCEND RATE", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_descendRate, 100, 500, 1 }, REBOOT_REQUIRED },
|
||||
{ "ARM WITHOUT FIX", OME_Bool, NULL, &gpsRescueConfig_allowArmingWithoutFix, REBOOT_REQUIRED },
|
||||
{ "MIN SATELITES", OME_UINT8, NULL, &(OSD_UINT8_t){ &gpsRescueConfig_minSats, 5, 50, 1 }, REBOOT_REQUIRED },
|
||||
{ "GPS RESCUE PID", OME_Submenu, cmsMenuChange, &cms_menuGpsRescuePid, 0},
|
||||
{ "ANGLE", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_angle, 0, 200 ,1 } },
|
||||
{ "MIN DIST HOME M", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_minRescueDth, 50, 1000 ,1 } },
|
||||
{ "INITAL ALT M", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_initialAltitudeM, 20, 100, 1 } },
|
||||
{ "ALTITUDE MODE" , OME_TAB | REBOOT_REQUIRED, NULL, &(OSD_TAB_t) { &gpsRescueConfig_altitudeMode, 2, lookupTableRescueAltitudeMode} },
|
||||
{ "DESCENT DIST M", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_descentDistanceM, 30, 500, 1 } },
|
||||
{ "LANDING ALT M", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_targetLandingAltitudeM, 3, 10, 1 } },
|
||||
{ "LANDING DIST M", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_targetLandingDistanceM, 5, 15, 1 } },
|
||||
{ "GROUND SPEED CM/S", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_rescueGroundspeed, 30, 3000, 1 } },
|
||||
{ "THROTTLE MIN", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleMin, 1000, 2000, 1 } },
|
||||
{ "THROTTLE MAX", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleMax, 1000, 2000, 1 } },
|
||||
{ "THROTTLE HOV", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleHover, 1000, 2000, 1 } },
|
||||
{ "ASCEND RATE", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_ascendRate, 100, 2500, 1 } },
|
||||
{ "DESCEND RATE", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_descendRate, 100, 500, 1 } },
|
||||
{ "ARM WITHOUT FIX", OME_Bool | REBOOT_REQUIRED, NULL, &gpsRescueConfig_allowArmingWithoutFix },
|
||||
{ "MIN SATELITES", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t){ &gpsRescueConfig_minSats, 5, 50, 1 } },
|
||||
{ "GPS RESCUE PID", OME_Submenu, cmsMenuChange, &cms_menuGpsRescuePid},
|
||||
|
||||
{"BACK", OME_Back, NULL, NULL, 0},
|
||||
{NULL, OME_END, NULL, NULL, 0}
|
||||
{"BACK", OME_Back, NULL, NULL},
|
||||
{NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
CMS_Menu cmsx_menuGpsRescue = {
|
||||
|
|
|
@ -195,27 +195,27 @@ static const void *cmsx_PidWriteback(displayPort_t *pDisp, const OSD_Entry *self
|
|||
return NULL;
|
||||
}
|
||||
|
||||
static const OSD_Entry cmsx_menuPidEntries[] =
|
||||
static OSD_Entry cmsx_menuPidEntries[] =
|
||||
{
|
||||
{ "-- PID --", OME_Label, NULL, pidProfileIndexString, 0},
|
||||
{ "-- PID --", OME_Label, NULL, pidProfileIndexString},
|
||||
|
||||
{ "ROLL P", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PID_ROLL][0], 0, 200, 1 }, 0 },
|
||||
{ "ROLL I", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PID_ROLL][1], 0, 200, 1 }, 0 },
|
||||
{ "ROLL D", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PID_ROLL][2], 0, 200, 1 }, 0 },
|
||||
{ "ROLL F", OME_UINT16, NULL, &(OSD_UINT16_t){ &tempPidF[PID_ROLL], 0, 2000, 1 }, 0 },
|
||||
{ "ROLL P", OME_UINT8 | SLIDER_RP, NULL, &(OSD_UINT8_t){ &tempPid[PID_ROLL][0], 0, 200, 1 }},
|
||||
{ "ROLL I", OME_UINT8 | SLIDER_RP, NULL, &(OSD_UINT8_t){ &tempPid[PID_ROLL][1], 0, 200, 1 }},
|
||||
{ "ROLL D", OME_UINT8 | SLIDER_RP, NULL, &(OSD_UINT8_t){ &tempPid[PID_ROLL][2], 0, 200, 1 }},
|
||||
{ "ROLL F", OME_UINT16 | SLIDER_RP, NULL, &(OSD_UINT16_t){ &tempPidF[PID_ROLL], 0, 2000, 1 }},
|
||||
|
||||
{ "PITCH P", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PID_PITCH][0], 0, 200, 1 }, 0 },
|
||||
{ "PITCH I", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PID_PITCH][1], 0, 200, 1 }, 0 },
|
||||
{ "PITCH D", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PID_PITCH][2], 0, 200, 1 }, 0 },
|
||||
{ "PITCH F", OME_UINT16, NULL, &(OSD_UINT16_t){ &tempPidF[PID_PITCH], 0, 2000, 1 }, 0 },
|
||||
{ "PITCH P", OME_UINT8 | SLIDER_RP, NULL, &(OSD_UINT8_t){ &tempPid[PID_PITCH][0], 0, 200, 1 }},
|
||||
{ "PITCH I", OME_UINT8 | SLIDER_RP, NULL, &(OSD_UINT8_t){ &tempPid[PID_PITCH][1], 0, 200, 1 }},
|
||||
{ "PITCH D", OME_UINT8 | SLIDER_RP, NULL, &(OSD_UINT8_t){ &tempPid[PID_PITCH][2], 0, 200, 1 }},
|
||||
{ "PITCH F", OME_UINT16 | SLIDER_RP, NULL, &(OSD_UINT16_t){ &tempPidF[PID_PITCH], 0, 2000, 1 }},
|
||||
|
||||
{ "YAW P", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PID_YAW][0], 0, 200, 1 }, 0 },
|
||||
{ "YAW I", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PID_YAW][1], 0, 200, 1 }, 0 },
|
||||
{ "YAW D", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PID_YAW][2], 0, 200, 1 }, 0 },
|
||||
{ "YAW F", OME_UINT16, NULL, &(OSD_UINT16_t){ &tempPidF[PID_YAW], 0, 2000, 1 }, 0 },
|
||||
{ "YAW P", OME_UINT8 | SLIDER_RPY, NULL, &(OSD_UINT8_t){ &tempPid[PID_YAW][0], 0, 200, 1 }},
|
||||
{ "YAW I", OME_UINT8 | SLIDER_RPY, NULL, &(OSD_UINT8_t){ &tempPid[PID_YAW][1], 0, 200, 1 }},
|
||||
{ "YAW D", OME_UINT8 | SLIDER_RPY, NULL, &(OSD_UINT8_t){ &tempPid[PID_YAW][2], 0, 200, 1 }},
|
||||
{ "YAW F", OME_UINT16 | SLIDER_RPY, NULL, &(OSD_UINT16_t){ &tempPidF[PID_YAW], 0, 2000, 1 }},
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
static CMS_Menu cmsx_menuPid = {
|
||||
|
@ -322,32 +322,32 @@ static const void *cmsx_simplifiedTuningOnExit(displayPort_t *pDisp, const OSD_E
|
|||
|
||||
static const OSD_Entry cmsx_menuSimplifiedTuningEntries[] =
|
||||
{
|
||||
{ "-- SIMPLIFIED PID --", OME_Label, NULL, NULL, 0},
|
||||
{ "PID TUNING", OME_TAB, NULL, &(OSD_TAB_t) { &cmsx_simplified_pids_mode, PID_SIMPLIFIED_TUNING_MODE_COUNT - 1, lookupTableSimplifiedTuningPidsMode }, 0 },
|
||||
{ "-- SIMPLIFIED PID --", OME_Label, NULL, NULL},
|
||||
{ "PID TUNING", OME_TAB, NULL, &(OSD_TAB_t) { &cmsx_simplified_pids_mode, PID_SIMPLIFIED_TUNING_MODE_COUNT - 1, lookupTableSimplifiedTuningPidsMode } },
|
||||
|
||||
{ "-- BASIC --", OME_Label, NULL, NULL, 0},
|
||||
{ "D GAINS", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_d_gain, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 }, 0 },
|
||||
{ "P&I GAINS", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_pi_gain, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 }, 0 },
|
||||
{ "FF GAINS", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_feedforward_gain, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 }, 0 },
|
||||
{ "-- BASIC --", OME_Label, NULL, NULL},
|
||||
{ "D GAINS", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_d_gain, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 } },
|
||||
{ "P&I GAINS", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_pi_gain, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 } },
|
||||
{ "FF GAINS", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_feedforward_gain, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 } },
|
||||
|
||||
{ "-- EXPERT --", OME_Label, NULL, NULL, 0},
|
||||
{ "-- EXPERT --", OME_Label, NULL, NULL},
|
||||
#ifdef USE_D_MIN
|
||||
{ "D MAX", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_dmin_ratio, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 }, 0 },
|
||||
{ "D MAX", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_dmin_ratio, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 } },
|
||||
#endif
|
||||
{ "I GAINS", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_i_gain, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 }, 0 },
|
||||
{ "I GAINS", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_i_gain, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 } },
|
||||
|
||||
{ "PITCH:ROLL D", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_roll_pitch_ratio, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 }, 0 },
|
||||
{ "PITCH:ROLL P,I&FF", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_pitch_pi_gain, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 }, 0 },
|
||||
{ "MASTER MULT", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_master_multiplier, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 }, 0 },
|
||||
{ "PITCH:ROLL D", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_roll_pitch_ratio, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 } },
|
||||
{ "PITCH:ROLL P,I&FF", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_pitch_pi_gain, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 } },
|
||||
{ "MASTER MULT", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_master_multiplier, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 } },
|
||||
|
||||
{ "-- SIMPLIFIED FILTER --", OME_Label, NULL, NULL, 0},
|
||||
{ "GYRO TUNING", OME_TAB, NULL, &(OSD_TAB_t) { &cmsx_simplified_gyro_filter, 1, lookupTableOffOn }, 0 },
|
||||
{ "GYRO MULT", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_gyro_filter_multiplier, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 }, 0 },
|
||||
{ "DTERM TUNING", OME_TAB, NULL, &(OSD_TAB_t) { &cmsx_simplified_dterm_filter, 1, lookupTableOffOn }, 0 },
|
||||
{ "DTERM MULT", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_dterm_filter_multiplier, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 }, 0 },
|
||||
{ "-- SIMPLIFIED FILTER --", OME_Label, NULL, NULL},
|
||||
{ "GYRO TUNING", OME_TAB, NULL, &(OSD_TAB_t) { &cmsx_simplified_gyro_filter, 1, lookupTableOffOn } },
|
||||
{ "GYRO MULT", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_gyro_filter_multiplier, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 } },
|
||||
{ "DTERM TUNING", OME_TAB, NULL, &(OSD_TAB_t) { &cmsx_simplified_dterm_filter, 1, lookupTableOffOn } },
|
||||
{ "DTERM MULT", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_simplified_dterm_filter_multiplier, SIMPLIFIED_TUNING_MIN, SIMPLIFIED_TUNING_MAX, 5, 10 } },
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
static CMS_Menu cmsx_menuSimplifiedTuning = {
|
||||
|
@ -394,33 +394,33 @@ static const void *cmsx_RateProfileOnEnter(displayPort_t *pDisp)
|
|||
|
||||
static const OSD_Entry cmsx_menuRateProfileEntries[] =
|
||||
{
|
||||
{ "-- RATE --", OME_Label, NULL, rateProfileIndexString, 0 },
|
||||
{ "-- RATE --", OME_Label, NULL, rateProfileIndexString },
|
||||
|
||||
{ "RC R RATE", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcRates[FD_ROLL], 1, CONTROL_RATE_CONFIG_RC_RATES_MAX, 1, 10 }, 0 },
|
||||
{ "RC P RATE", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcRates[FD_PITCH], 1, CONTROL_RATE_CONFIG_RC_RATES_MAX, 1, 10 }, 0 },
|
||||
{ "RC Y RATE", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcRates[FD_YAW], 1, CONTROL_RATE_CONFIG_RC_RATES_MAX, 1, 10 }, 0 },
|
||||
{ "RC R RATE", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcRates[FD_ROLL], 1, CONTROL_RATE_CONFIG_RC_RATES_MAX, 1, 10 } },
|
||||
{ "RC P RATE", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcRates[FD_PITCH], 1, CONTROL_RATE_CONFIG_RC_RATES_MAX, 1, 10 } },
|
||||
{ "RC Y RATE", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcRates[FD_YAW], 1, CONTROL_RATE_CONFIG_RC_RATES_MAX, 1, 10 } },
|
||||
|
||||
{ "ROLL SUPER", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rates[FD_ROLL], 0, CONTROL_RATE_CONFIG_RATE_MAX, 1, 10 }, 0 },
|
||||
{ "PITCH SUPER", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rates[FD_PITCH], 0, CONTROL_RATE_CONFIG_RATE_MAX, 1, 10 }, 0 },
|
||||
{ "YAW SUPER", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rates[FD_YAW], 0, CONTROL_RATE_CONFIG_RATE_MAX, 1, 10 }, 0 },
|
||||
{ "ROLL SUPER", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rates[FD_ROLL], 0, CONTROL_RATE_CONFIG_RATE_MAX, 1, 10 } },
|
||||
{ "PITCH SUPER", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rates[FD_PITCH], 0, CONTROL_RATE_CONFIG_RATE_MAX, 1, 10 } },
|
||||
{ "YAW SUPER", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rates[FD_YAW], 0, CONTROL_RATE_CONFIG_RATE_MAX, 1, 10 } },
|
||||
|
||||
{ "RC R EXPO", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcExpo[FD_ROLL], 0, 100, 1, 10 }, 0 },
|
||||
{ "RC P EXPO", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcExpo[FD_PITCH], 0, 100, 1, 10 }, 0 },
|
||||
{ "RC Y EXPO", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcExpo[FD_YAW], 0, 100, 1, 10 }, 0 },
|
||||
{ "RC R EXPO", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcExpo[FD_ROLL], 0, 100, 1, 10 } },
|
||||
{ "RC P EXPO", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcExpo[FD_PITCH], 0, 100, 1, 10 } },
|
||||
{ "RC Y EXPO", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcExpo[FD_YAW], 0, 100, 1, 10 } },
|
||||
|
||||
{ "THR MID", OME_UINT8, NULL, &(OSD_UINT8_t) { &rateProfile.thrMid8, 0, 100, 1}, 0 },
|
||||
{ "THR EXPO", OME_UINT8, NULL, &(OSD_UINT8_t) { &rateProfile.thrExpo8, 0, 100, 1}, 0 },
|
||||
{ "THRPID ATT", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.dynThrPID, 0, 100, 1, 10}, 0 },
|
||||
{ "TPA BRKPT", OME_UINT16, NULL, &(OSD_UINT16_t){ &rateProfile.tpa_breakpoint, 1000, 2000, 10}, 0 },
|
||||
{ "THR MID", OME_UINT8, NULL, &(OSD_UINT8_t) { &rateProfile.thrMid8, 0, 100, 1} },
|
||||
{ "THR EXPO", OME_UINT8, NULL, &(OSD_UINT8_t) { &rateProfile.thrExpo8, 0, 100, 1} },
|
||||
{ "THRPID ATT", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.dynThrPID, 0, 100, 1, 10} },
|
||||
{ "TPA BRKPT", OME_UINT16, NULL, &(OSD_UINT16_t){ &rateProfile.tpa_breakpoint, 1000, 2000, 10} },
|
||||
|
||||
{ "THR LIM TYPE",OME_TAB, NULL, &(OSD_TAB_t) { &rateProfile.throttle_limit_type, THROTTLE_LIMIT_TYPE_COUNT - 1, osdTableThrottleLimitType}, 0 },
|
||||
{ "THR LIM %", OME_UINT8, NULL, &(OSD_UINT8_t) { &rateProfile.throttle_limit_percent, 25, 100, 1}, 0 },
|
||||
{ "THR LIM TYPE",OME_TAB, NULL, &(OSD_TAB_t) { &rateProfile.throttle_limit_type, THROTTLE_LIMIT_TYPE_COUNT - 1, osdTableThrottleLimitType} },
|
||||
{ "THR LIM %", OME_UINT8, NULL, &(OSD_UINT8_t) { &rateProfile.throttle_limit_percent, 25, 100, 1} },
|
||||
|
||||
{ "ROLL LVL EXPO", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.levelExpo[FD_ROLL], 0, 100, 1, 10 }, 0 },
|
||||
{ "PITCH LVL EXPO", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.levelExpo[FD_PITCH], 0, 100, 1, 10 }, 0 },
|
||||
{ "ROLL LVL EXPO", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.levelExpo[FD_ROLL], 0, 100, 1, 10 } },
|
||||
{ "PITCH LVL EXPO", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.levelExpo[FD_PITCH], 0, 100, 1, 10 } },
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
static CMS_Menu cmsx_menuRateProfile = {
|
||||
|
@ -473,16 +473,16 @@ static const void *cmsx_launchControlOnExit(displayPort_t *pDisp, const OSD_Entr
|
|||
}
|
||||
|
||||
static const OSD_Entry cmsx_menuLaunchControlEntries[] = {
|
||||
{ "-- LAUNCH CONTROL --", OME_Label, NULL, pidProfileIndexString, 0 },
|
||||
{ "-- LAUNCH CONTROL --", OME_Label, NULL, pidProfileIndexString },
|
||||
|
||||
{ "MODE", OME_TAB, NULL, &(OSD_TAB_t) { &cmsx_launchControlMode, LAUNCH_CONTROL_MODE_COUNT - 1, osdLaunchControlModeNames}, 0 },
|
||||
{ "ALLOW RESET", OME_Bool, NULL, &cmsx_launchControlAllowTriggerReset, 0 },
|
||||
{ "TRIGGER THROTTLE", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_launchControlThrottlePercent, 0, LAUNCH_CONTROL_THROTTLE_TRIGGER_MAX, 1 } , 0 },
|
||||
{ "ANGLE LIMIT", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_launchControlAngleLimit, 0, 80, 1 } , 0 },
|
||||
{ "ITERM GAIN", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_launchControlGain, 0, 200, 1 } , 0 },
|
||||
{ "MODE", OME_TAB, NULL, &(OSD_TAB_t) { &cmsx_launchControlMode, LAUNCH_CONTROL_MODE_COUNT - 1, osdLaunchControlModeNames} },
|
||||
{ "ALLOW RESET", OME_Bool, NULL, &cmsx_launchControlAllowTriggerReset },
|
||||
{ "TRIGGER THROTTLE", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_launchControlThrottlePercent, 0, LAUNCH_CONTROL_THROTTLE_TRIGGER_MAX, 1 } },
|
||||
{ "ANGLE LIMIT", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_launchControlAngleLimit, 0, 80, 1 } },
|
||||
{ "ITERM GAIN", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_launchControlGain, 0, 200, 1 } },
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
static CMS_Menu cmsx_menuLaunchControl = {
|
||||
|
@ -575,6 +575,7 @@ static const void *cmsx_profileOtherOnEnter(displayPort_t *pDisp)
|
|||
#ifdef USE_BATTERY_VOLTAGE_SAG_COMPENSATION
|
||||
cmsx_vbat_sag_compensation = pidProfile->vbat_sag_compensation;
|
||||
#endif
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
||||
|
@ -629,52 +630,52 @@ static const void *cmsx_profileOtherOnExit(displayPort_t *pDisp, const OSD_Entry
|
|||
}
|
||||
|
||||
static const OSD_Entry cmsx_menuProfileOtherEntries[] = {
|
||||
{ "-- OTHER PP --", OME_Label, NULL, pidProfileIndexString, 0 },
|
||||
{ "-- OTHER PP --", OME_Label, NULL, pidProfileIndexString },
|
||||
|
||||
#ifdef USE_FEEDFORWARD
|
||||
{ "FF TRANSITION", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_feedforward_transition, 0, 100, 1, 10 }, 0 },
|
||||
{ "FF AVERAGING", OME_TAB, NULL, &(OSD_TAB_t) { &cmsx_feedforward_averaging, 4, lookupTableFeedforwardAveraging}, 0 },
|
||||
{ "FF SMOOTHNESS", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_feedforward_smooth_factor, 0, 75, 1 } , 0 },
|
||||
{ "FF JITTER", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_feedforward_jitter_factor, 0, 20, 1 } , 0 },
|
||||
{ "FF BOOST", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_feedforward_boost, 0, 50, 1 } , 0 },
|
||||
{ "FF TRANSITION", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_feedforward_transition, 0, 100, 1, 10 } },
|
||||
{ "FF AVERAGING", OME_TAB, NULL, &(OSD_TAB_t) { &cmsx_feedforward_averaging, 4, lookupTableFeedforwardAveraging} },
|
||||
{ "FF SMOOTHNESS", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_feedforward_smooth_factor, 0, 75, 1 } },
|
||||
{ "FF JITTER", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_feedforward_jitter_factor, 0, 20, 1 } },
|
||||
{ "FF BOOST", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_feedforward_boost, 0, 50, 1 } },
|
||||
#endif
|
||||
{ "ANGLE STR", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_angleStrength, 0, 200, 1 } , 0 },
|
||||
{ "HORZN STR", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_horizonStrength, 0, 200, 1 } , 0 },
|
||||
{ "HORZN TRS", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_horizonTransition, 0, 200, 1 } , 0 },
|
||||
{ "AG GAIN", OME_UINT16, NULL, &(OSD_UINT16_t) { &cmsx_itermAcceleratorGain, ITERM_ACCELERATOR_GAIN_OFF, ITERM_ACCELERATOR_GAIN_MAX, 10 } , 0 },
|
||||
{ "AG THR", OME_UINT16, NULL, &(OSD_UINT16_t) { &cmsx_itermThrottleThreshold, 20, 1000, 1 } , 0 },
|
||||
{ "ANGLE STR", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_angleStrength, 0, 200, 1 } },
|
||||
{ "HORZN STR", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_horizonStrength, 0, 200, 1 } },
|
||||
{ "HORZN TRS", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_horizonTransition, 0, 200, 1 } },
|
||||
{ "AG GAIN", OME_UINT16, NULL, &(OSD_UINT16_t) { &cmsx_itermAcceleratorGain, ITERM_ACCELERATOR_GAIN_OFF, ITERM_ACCELERATOR_GAIN_MAX, 10 } },
|
||||
{ "AG THR", OME_UINT16, NULL, &(OSD_UINT16_t) { &cmsx_itermThrottleThreshold, 20, 1000, 1 } },
|
||||
#ifdef USE_THROTTLE_BOOST
|
||||
{ "THR BOOST", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_throttleBoost, 0, 100, 1 } , 0 },
|
||||
{ "THR BOOST", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_throttleBoost, 0, 100, 1 } },
|
||||
#endif
|
||||
#ifdef USE_THRUST_LINEARIZATION
|
||||
{ "THR LINEAR", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_thrustLinearization, 0, 150, 1 } , 0 },
|
||||
{ "THR LINEAR", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_thrustLinearization, 0, 150, 1 } },
|
||||
#endif
|
||||
#ifdef USE_ITERM_RELAX
|
||||
{ "I_RELAX", OME_TAB, NULL, &(OSD_TAB_t) { &cmsx_iterm_relax, ITERM_RELAX_COUNT - 1, lookupTableItermRelax }, 0 },
|
||||
{ "I_RELAX TYPE", OME_TAB, NULL, &(OSD_TAB_t) { &cmsx_iterm_relax_type, ITERM_RELAX_TYPE_COUNT - 1, lookupTableItermRelaxType }, 0 },
|
||||
{ "I_RELAX CUTOFF", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_iterm_relax_cutoff, 1, 50, 1 }, 0 },
|
||||
{ "I_RELAX", OME_TAB, NULL, &(OSD_TAB_t) { &cmsx_iterm_relax, ITERM_RELAX_COUNT - 1, lookupTableItermRelax } },
|
||||
{ "I_RELAX TYPE", OME_TAB, NULL, &(OSD_TAB_t) { &cmsx_iterm_relax_type, ITERM_RELAX_TYPE_COUNT - 1, lookupTableItermRelaxType } },
|
||||
{ "I_RELAX CUTOFF", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_iterm_relax_cutoff, 1, 50, 1 } },
|
||||
#endif
|
||||
#ifdef USE_LAUNCH_CONTROL
|
||||
{"LAUNCH CONTROL", OME_Submenu, cmsMenuChange, &cmsx_menuLaunchControl, 0 },
|
||||
{"LAUNCH CONTROL", OME_Submenu, cmsMenuChange, &cmsx_menuLaunchControl },
|
||||
#endif
|
||||
{ "MTR OUT LIM %",OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_motorOutputLimit, MOTOR_OUTPUT_LIMIT_PERCENT_MIN, MOTOR_OUTPUT_LIMIT_PERCENT_MAX, 1}, 0 },
|
||||
{ "MTR OUT LIM %",OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_motorOutputLimit, MOTOR_OUTPUT_LIMIT_PERCENT_MIN, MOTOR_OUTPUT_LIMIT_PERCENT_MAX, 1} },
|
||||
|
||||
{ "AUTO CELL CNT", OME_INT8, NULL, &(OSD_INT8_t) { &cmsx_autoProfileCellCount, AUTO_PROFILE_CELL_COUNT_CHANGE, MAX_AUTO_DETECT_CELL_COUNT, 1}, 0 },
|
||||
{ "AUTO CELL CNT", OME_INT8, NULL, &(OSD_INT8_t) { &cmsx_autoProfileCellCount, AUTO_PROFILE_CELL_COUNT_CHANGE, MAX_AUTO_DETECT_CELL_COUNT, 1} },
|
||||
|
||||
#ifdef USE_D_MIN
|
||||
{ "D_MIN ROLL", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_d_min[FD_ROLL], 0, 100, 1 }, 0 },
|
||||
{ "D_MIN PITCH", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_d_min[FD_PITCH], 0, 100, 1 }, 0 },
|
||||
{ "D_MIN YAW", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_d_min[FD_YAW], 0, 100, 1 }, 0 },
|
||||
{ "D_MIN GAIN", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_d_min_gain, 0, 100, 1 }, 0 },
|
||||
{ "D_MIN ADV", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_d_min_advance, 0, 200, 1 }, 0 },
|
||||
{ "D_MIN ROLL", OME_UINT8 | SLIDER_RP, NULL, &(OSD_UINT8_t) { &cmsx_d_min[FD_ROLL], 0, 100, 1 } },
|
||||
{ "D_MIN PITCH", OME_UINT8 | SLIDER_RP, NULL, &(OSD_UINT8_t) { &cmsx_d_min[FD_PITCH], 0, 100, 1 } },
|
||||
{ "D_MIN YAW", OME_UINT8 | SLIDER_RPY, NULL, &(OSD_UINT8_t) { &cmsx_d_min[FD_YAW], 0, 100, 1 } },
|
||||
{ "D_MIN GAIN", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_d_min_gain, 0, 100, 1 } },
|
||||
{ "D_MIN ADV", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_d_min_advance, 0, 200, 1 } },
|
||||
#endif
|
||||
|
||||
#ifdef USE_BATTERY_VOLTAGE_SAG_COMPENSATION
|
||||
{ "VBAT_SAG_COMP", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_vbat_sag_compensation, 0, 150, 1 }, 0 },
|
||||
{ "VBAT_SAG_COMP", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_vbat_sag_compensation, 0, 150, 1 } },
|
||||
#endif
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
static CMS_Menu cmsx_menuProfileOther = {
|
||||
|
@ -730,22 +731,22 @@ static const void *cmsx_menuGyro_onExit(displayPort_t *pDisp, const OSD_Entry *s
|
|||
|
||||
static const OSD_Entry cmsx_menuFilterGlobalEntries[] =
|
||||
{
|
||||
{ "-- FILTER GLB --", OME_Label, NULL, NULL, 0 },
|
||||
{ "-- FILTER GLB --", OME_Label, NULL, NULL },
|
||||
|
||||
{ "GYRO LPF1", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_lpf1_static_hz, 0, LPF_MAX_HZ, 1 }, 0 },
|
||||
{ "GYRO LPF1", OME_UINT16 | SLIDER_GYRO, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_lpf1_static_hz, 0, LPF_MAX_HZ, 1 } },
|
||||
#ifdef USE_GYRO_LPF2
|
||||
{ "GYRO LPF2", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_lpf2_static_hz, 0, LPF_MAX_HZ, 1 }, 0 },
|
||||
{ "GYRO LPF2", OME_UINT16 | SLIDER_GYRO, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_lpf2_static_hz, 0, LPF_MAX_HZ, 1 } },
|
||||
#endif
|
||||
{ "GYRO NF1", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_soft_notch_hz_1, 0, 500, 1 }, 0 },
|
||||
{ "GYRO NF1C", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_soft_notch_cutoff_1, 0, 500, 1 }, 0 },
|
||||
{ "GYRO NF2", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_soft_notch_hz_2, 0, 500, 1 }, 0 },
|
||||
{ "GYRO NF2C", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_soft_notch_cutoff_2, 0, 500, 1 }, 0 },
|
||||
{ "GYRO NF1", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_soft_notch_hz_1, 0, 500, 1 } },
|
||||
{ "GYRO NF1C", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_soft_notch_cutoff_1, 0, 500, 1 } },
|
||||
{ "GYRO NF2", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_soft_notch_hz_2, 0, 500, 1 } },
|
||||
{ "GYRO NF2C", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_soft_notch_cutoff_2, 0, 500, 1 } },
|
||||
#ifdef USE_MULTI_GYRO
|
||||
{ "GYRO TO USE", OME_TAB, NULL, &(OSD_TAB_t) { &gyroConfig_gyro_to_use, 2, osdTableGyroToUse}, REBOOT_REQUIRED },
|
||||
{ "GYRO TO USE", OME_TAB | REBOOT_REQUIRED, NULL, &(OSD_TAB_t) { &gyroConfig_gyro_to_use, 2, osdTableGyroToUse} },
|
||||
#endif
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
static CMS_Menu cmsx_menuFilterGlobal = {
|
||||
|
@ -825,26 +826,26 @@ static const void *cmsx_menuDynFilt_onExit(displayPort_t *pDisp, const OSD_Entry
|
|||
|
||||
static const OSD_Entry cmsx_menuDynFiltEntries[] =
|
||||
{
|
||||
{ "-- DYN FILT --", OME_Label, NULL, NULL, 0 },
|
||||
{ "-- DYN FILT --", OME_Label, NULL, NULL },
|
||||
|
||||
#ifdef USE_DYN_NOTCH_FILTER
|
||||
{ "NOTCH COUNT", OME_UINT8, NULL, &(OSD_UINT8_t) { &dynFiltNotchCount, 0, DYN_NOTCH_COUNT_MAX, 1 }, 0 },
|
||||
{ "NOTCH Q", OME_UINT16, NULL, &(OSD_UINT16_t) { &dynFiltNotchQ, 1, 1000, 1 }, 0 },
|
||||
{ "NOTCH MIN HZ", OME_UINT16, NULL, &(OSD_UINT16_t) { &dynFiltNotchMinHz, 60, 250, 1 }, 0 },
|
||||
{ "NOTCH MAX HZ", OME_UINT16, NULL, &(OSD_UINT16_t) { &dynFiltNotchMaxHz, 200, 1000, 1 }, 0 },
|
||||
{ "NOTCH COUNT", OME_UINT8, NULL, &(OSD_UINT8_t) { &dynFiltNotchCount, 0, DYN_NOTCH_COUNT_MAX, 1 } },
|
||||
{ "NOTCH Q", OME_UINT16, NULL, &(OSD_UINT16_t) { &dynFiltNotchQ, 1, 1000, 1 } },
|
||||
{ "NOTCH MIN HZ", OME_UINT16, NULL, &(OSD_UINT16_t) { &dynFiltNotchMinHz, 60, 250, 1 } },
|
||||
{ "NOTCH MAX HZ", OME_UINT16, NULL, &(OSD_UINT16_t) { &dynFiltNotchMaxHz, 200, 1000, 1 } },
|
||||
#endif
|
||||
|
||||
#ifdef USE_DYN_LPF
|
||||
{ "GYRO DLPF MIN", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroLpfDynMin, 0, 1000, 1 }, 0 },
|
||||
{ "GYRO DLPF MAX", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroLpfDynMax, 0, 1000, 1 }, 0 },
|
||||
{ "GYRO DLPF EXPO", OME_UINT8, NULL, &(OSD_UINT8_t) { &gyroLpfDynExpo, 0, 10, 1 }, 0 },
|
||||
{ "DTERM DLPF MIN", OME_UINT16, NULL, &(OSD_UINT16_t) { &dtermLpfDynMin, 0, 1000, 1 }, 0 },
|
||||
{ "DTERM DLPF MAX", OME_UINT16, NULL, &(OSD_UINT16_t) { &dtermLpfDynMax, 0, 1000, 1 }, 0 },
|
||||
{ "DTERM DLPF EXPO", OME_UINT8, NULL, &(OSD_UINT8_t) { &dtermLpfDynExpo, 0, 10, 1 }, 0 },
|
||||
{ "GYRO DLPF MIN", OME_UINT16 | SLIDER_GYRO, NULL, &(OSD_UINT16_t) { &gyroLpfDynMin, 0, 1000, 1 } },
|
||||
{ "GYRO DLPF MAX", OME_UINT16 | SLIDER_GYRO, NULL, &(OSD_UINT16_t) { &gyroLpfDynMax, 0, 1000, 1 } },
|
||||
{ "GYRO DLPF EXPO", OME_UINT8, NULL, &(OSD_UINT8_t) { &gyroLpfDynExpo, 0, 10, 1 } },
|
||||
{ "DTERM DLPF MIN", OME_UINT16 | SLIDER_DTERM, NULL, &(OSD_UINT16_t) { &dtermLpfDynMin, 0, 1000, 1 } },
|
||||
{ "DTERM DLPF MAX", OME_UINT16 | SLIDER_DTERM, NULL, &(OSD_UINT16_t) { &dtermLpfDynMax, 0, 1000, 1 } },
|
||||
{ "DTERM DLPF EXPO", OME_UINT8, NULL, &(OSD_UINT8_t) { &dtermLpfDynExpo, 0, 10, 1 } },
|
||||
#endif
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
static CMS_Menu cmsx_menuDynFilt = {
|
||||
|
@ -899,16 +900,16 @@ static const void *cmsx_FilterPerProfileWriteback(displayPort_t *pDisp, const OS
|
|||
|
||||
static const OSD_Entry cmsx_menuFilterPerProfileEntries[] =
|
||||
{
|
||||
{ "-- FILTER PP --", OME_Label, NULL, NULL, 0 },
|
||||
{ "-- FILTER PP --", OME_Label, NULL, NULL },
|
||||
|
||||
{ "DTERM LPF1", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_lpf1_static_hz, 0, LPF_MAX_HZ, 1 }, 0 },
|
||||
{ "DTERM LPF2", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_lpf2_static_hz, 0, LPF_MAX_HZ, 1 }, 0 },
|
||||
{ "DTERM NF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_notch_hz, 0, LPF_MAX_HZ, 1 }, 0 },
|
||||
{ "DTERM NFCO", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_notch_cutoff, 0, LPF_MAX_HZ, 1 }, 0 },
|
||||
{ "YAW LPF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_yaw_lowpass_hz, 0, 500, 1 }, 0 },
|
||||
{ "DTERM LPF1", OME_UINT16 | SLIDER_DTERM, NULL, &(OSD_UINT16_t){ &cmsx_dterm_lpf1_static_hz, 0, LPF_MAX_HZ, 1 } },
|
||||
{ "DTERM LPF2", OME_UINT16 | SLIDER_DTERM, NULL, &(OSD_UINT16_t){ &cmsx_dterm_lpf2_static_hz, 0, LPF_MAX_HZ, 1 } },
|
||||
{ "DTERM NF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_notch_hz, 0, LPF_MAX_HZ, 1 } },
|
||||
{ "DTERM NFCO", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_notch_cutoff, 0, LPF_MAX_HZ, 1 } },
|
||||
{ "YAW LPF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_yaw_lowpass_hz, 0, 500, 1 } },
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
static CMS_Menu cmsx_menuFilterPerProfile = {
|
||||
|
@ -973,15 +974,15 @@ static const void *cmsx_CopyControlRateProfile(displayPort_t *pDisplay, const vo
|
|||
|
||||
static const OSD_Entry cmsx_menuCopyProfileEntries[] =
|
||||
{
|
||||
{ "-- COPY PROFILE --", OME_Label, NULL, NULL, 0},
|
||||
{ "-- COPY PROFILE --", OME_Label, NULL, NULL},
|
||||
|
||||
{ "CPY PID PROF TO", OME_TAB, NULL, &cmsx_PidProfileTable, 0 },
|
||||
{ "COPY PP", OME_Funcall, cmsx_CopyPidProfile, NULL, 0 },
|
||||
{ "CPY RATE PROF TO", OME_TAB, NULL, &cmsx_ControlRateProfileTable, 0 },
|
||||
{ "COPY RP", OME_Funcall, cmsx_CopyControlRateProfile, NULL, 0 },
|
||||
{ "CPY PID PROF TO", OME_TAB, NULL, &cmsx_PidProfileTable },
|
||||
{ "COPY PP", OME_Funcall, cmsx_CopyPidProfile, NULL },
|
||||
{ "CPY RATE PROF TO", OME_TAB, NULL, &cmsx_ControlRateProfileTable },
|
||||
{ "COPY RP", OME_Funcall, cmsx_CopyControlRateProfile, NULL },
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
CMS_Menu cmsx_menuCopyProfile = {
|
||||
|
@ -999,30 +1000,30 @@ CMS_Menu cmsx_menuCopyProfile = {
|
|||
|
||||
static const OSD_Entry cmsx_menuImuEntries[] =
|
||||
{
|
||||
{ "-- PROFILE --", OME_Label, NULL, NULL, 0},
|
||||
{ "-- PROFILE --", OME_Label, NULL, NULL},
|
||||
|
||||
{"PID PROF", OME_UINT8, cmsx_profileIndexOnChange, &(OSD_UINT8_t){ &tmpPidProfileIndex, 1, PID_PROFILE_COUNT, 1}, 0},
|
||||
{"PID", OME_Submenu, cmsMenuChange, &cmsx_menuPid, 0},
|
||||
{"PID PROF", OME_UINT8, cmsx_profileIndexOnChange, &(OSD_UINT8_t){ &tmpPidProfileIndex, 1, PID_PROFILE_COUNT, 1}},
|
||||
{"PID", OME_Submenu, cmsMenuChange, &cmsx_menuPid},
|
||||
#ifdef USE_SIMPLIFIED_TUNING
|
||||
{"SIMPLIFIED TUNING", OME_Submenu, cmsMenuChange, &cmsx_menuSimplifiedTuning, 0},
|
||||
{"SIMPLIFIED TUNING", OME_Submenu, cmsMenuChange, &cmsx_menuSimplifiedTuning},
|
||||
#endif
|
||||
{"MISC PP", OME_Submenu, cmsMenuChange, &cmsx_menuProfileOther, 0},
|
||||
{"FILT PP", OME_Submenu, cmsMenuChange, &cmsx_menuFilterPerProfile, 0},
|
||||
{"MISC PP", OME_Submenu, cmsMenuChange, &cmsx_menuProfileOther},
|
||||
{"FILT PP", OME_Submenu, cmsMenuChange, &cmsx_menuFilterPerProfile},
|
||||
|
||||
{"RATE PROF", OME_UINT8, cmsx_rateProfileIndexOnChange, &(OSD_UINT8_t){ &tmpRateProfileIndex, 1, CONTROL_RATE_PROFILE_COUNT, 1}, 0},
|
||||
{"RATE", OME_Submenu, cmsMenuChange, &cmsx_menuRateProfile, 0},
|
||||
{"RATE PROF", OME_UINT8, cmsx_rateProfileIndexOnChange, &(OSD_UINT8_t){ &tmpRateProfileIndex, 1, CONTROL_RATE_PROFILE_COUNT, 1}},
|
||||
{"RATE", OME_Submenu, cmsMenuChange, &cmsx_menuRateProfile},
|
||||
|
||||
{"FILT GLB", OME_Submenu, cmsMenuChange, &cmsx_menuFilterGlobal, 0},
|
||||
{"FILT GLB", OME_Submenu, cmsMenuChange, &cmsx_menuFilterGlobal},
|
||||
#if (defined(USE_DYN_NOTCH_FILTER) || defined(USE_DYN_LPF)) && defined(USE_EXTENDED_CMS_MENUS)
|
||||
{"DYN FILT", OME_Submenu, cmsMenuChange, &cmsx_menuDynFilt, 0},
|
||||
{"DYN FILT", OME_Submenu, cmsMenuChange, &cmsx_menuDynFilt},
|
||||
#endif
|
||||
|
||||
#ifdef USE_EXTENDED_CMS_MENUS
|
||||
{"COPY PROF", OME_Submenu, cmsMenuChange, &cmsx_menuCopyProfile, 0},
|
||||
{"COPY PROF", OME_Submenu, cmsMenuChange, &cmsx_menuCopyProfile},
|
||||
#endif /* USE_EXTENDED_CMS_MENUS */
|
||||
|
||||
{"BACK", OME_Back, NULL, NULL, 0},
|
||||
{NULL, OME_END, NULL, NULL, 0}
|
||||
{"BACK", OME_Back, NULL, NULL},
|
||||
{NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
CMS_Menu cmsx_menuImu = {
|
||||
|
|
|
@ -109,18 +109,18 @@ static const void *cmsx_Ledstrip_OnExit(displayPort_t *pDisp, const OSD_Entry *s
|
|||
|
||||
static const OSD_Entry cmsx_menuLedstripEntries[] =
|
||||
{
|
||||
{ "-- LED STRIP --", OME_Label, NULL, NULL, 0 },
|
||||
{ "ENABLED", OME_Bool, NULL, &cmsx_FeatureLedstrip, 0 },
|
||||
{ "PROFILE", OME_TAB, NULL, &(OSD_TAB_t){ &cmsx_ledProfile, LED_PROFILE_COUNT - 1, ledProfileNames }, 0 },
|
||||
{ "RACE COLOR", OME_TAB, NULL, &(OSD_TAB_t){ &cmsx_ledRaceColor, COLOR_COUNT - 1, lookupTableLedstripColors }, 0 },
|
||||
{ "BEACON COLOR", OME_TAB, NULL, &(OSD_TAB_t){ &cmsx_ledBeaconColor, COLOR_COUNT -1, lookupTableLedstripColors }, 0 },
|
||||
{ "BEACON PERIOD", OME_UINT16,NULL, &(OSD_UINT16_t){ &cmsx_ledBeaconPeriod, 50, 10000, 10 }, 0 },
|
||||
{ "BEACON ON %", OME_UINT8, NULL, &(OSD_UINT8_t){ &cmsx_ledBeaconOnPercent, 0, 100, 1 }, 0 },
|
||||
{ "BEACON ARMED ONLY",OME_Bool, NULL, &cmsx_ledBeaconArmedOnly, 0 },
|
||||
{ "VISUAL BEEPER", OME_Bool, NULL, &cmsx_ledVisualBeeper, 0 },
|
||||
{ "VISUAL COLOR", OME_TAB, NULL, &(OSD_TAB_t){ &cmsx_ledVisualBeeperColor, COLOR_COUNT - 1, lookupTableLedstripColors }, 0 },
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "-- LED STRIP --", OME_Label, NULL, NULL },
|
||||
{ "ENABLED", OME_Bool, NULL, &cmsx_FeatureLedstrip },
|
||||
{ "PROFILE", OME_TAB, NULL, &(OSD_TAB_t){ &cmsx_ledProfile, LED_PROFILE_COUNT - 1, ledProfileNames } },
|
||||
{ "RACE COLOR", OME_TAB, NULL, &(OSD_TAB_t){ &cmsx_ledRaceColor, COLOR_COUNT - 1, lookupTableLedstripColors } },
|
||||
{ "BEACON COLOR", OME_TAB, NULL, &(OSD_TAB_t){ &cmsx_ledBeaconColor, COLOR_COUNT -1, lookupTableLedstripColors } },
|
||||
{ "BEACON PERIOD", OME_UINT16,NULL, &(OSD_UINT16_t){ &cmsx_ledBeaconPeriod, 50, 10000, 10 } },
|
||||
{ "BEACON ON %", OME_UINT8, NULL, &(OSD_UINT8_t){ &cmsx_ledBeaconOnPercent, 0, 100, 1 } },
|
||||
{ "BEACON ARMED ONLY",OME_Bool, NULL, &cmsx_ledBeaconArmedOnly },
|
||||
{ "VISUAL BEEPER", OME_Bool, NULL, &cmsx_ledVisualBeeper },
|
||||
{ "VISUAL COLOR", OME_TAB, NULL, &(OSD_TAB_t){ &cmsx_ledVisualBeeperColor, COLOR_COUNT - 1, lookupTableLedstripColors } },
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
CMS_Menu cmsx_menuLedstrip = {
|
||||
|
|
|
@ -76,28 +76,28 @@ static char accCalibrationStatus[CALIBRATION_STATUS_MAX_LENGTH];
|
|||
|
||||
static const OSD_Entry menuFeaturesEntries[] =
|
||||
{
|
||||
{"--- FEATURES ---", OME_Label, NULL, NULL, 0},
|
||||
{"--- FEATURES ---", OME_Label, NULL, NULL},
|
||||
|
||||
#if defined(USE_BLACKBOX)
|
||||
{"BLACKBOX", OME_Submenu, cmsMenuChange, &cmsx_menuBlackbox, 0},
|
||||
{"BLACKBOX", OME_Submenu, cmsMenuChange, &cmsx_menuBlackbox},
|
||||
#endif
|
||||
#if defined(USE_VTX_CONTROL)
|
||||
#if defined(USE_VTX_RTC6705) || defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP)
|
||||
{"VTX", OME_Funcall, cmsSelectVtx, NULL, 0},
|
||||
{"VTX", OME_Funcall, cmsSelectVtx, NULL},
|
||||
#endif
|
||||
#endif // VTX_CONTROL
|
||||
#ifdef USE_LED_STRIP
|
||||
{"LED STRIP", OME_Submenu, cmsMenuChange, &cmsx_menuLedstrip, 0},
|
||||
{"LED STRIP", OME_Submenu, cmsMenuChange, &cmsx_menuLedstrip},
|
||||
#endif // LED_STRIP
|
||||
{"POWER", OME_Submenu, cmsMenuChange, &cmsx_menuPower, 0},
|
||||
{"POWER", OME_Submenu, cmsMenuChange, &cmsx_menuPower},
|
||||
#ifdef USE_CMS_FAILSAFE_MENU
|
||||
{"FAILSAFE", OME_Submenu, cmsMenuChange, &cmsx_menuFailsafe, 0},
|
||||
{"FAILSAFE", OME_Submenu, cmsMenuChange, &cmsx_menuFailsafe},
|
||||
#endif
|
||||
#ifdef USE_PERSISTENT_STATS
|
||||
{"PERSISTENT STATS", OME_Submenu, cmsMenuChange, &cmsx_menuPersistentStats, 0},
|
||||
{"PERSISTENT STATS", OME_Submenu, cmsMenuChange, &cmsx_menuPersistentStats},
|
||||
#endif
|
||||
{"BACK", OME_Back, NULL, NULL, 0},
|
||||
{NULL, OME_END, NULL, NULL, 0}
|
||||
{"BACK", OME_Back, NULL, NULL},
|
||||
{NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
static CMS_Menu cmsx_menuFeatures = {
|
||||
|
@ -130,17 +130,17 @@ static bool setupPopupMenuBuild(void)
|
|||
uint8_t menuIndex = 0;
|
||||
updateArmingStatus();
|
||||
|
||||
cmsAddMenuEntry(&setupPopupMenuEntries[menuIndex], "-- SETUP MENU --", OME_Label, NULL, NULL, 0);
|
||||
cmsAddMenuEntry(&setupPopupMenuEntries[menuIndex], "-- SETUP MENU --", OME_Label, NULL, NULL);
|
||||
|
||||
// Add menu entries for uncompleted setup tasks
|
||||
#if defined(USE_ACC)
|
||||
if (sensors(SENSOR_ACC) && (getArmingDisableFlags() & ARMING_DISABLED_ACC_CALIBRATION)) {
|
||||
cmsAddMenuEntry(&setupPopupMenuEntries[++menuIndex], "CALIBRATE ACC", OME_Funcall, cmsCalibrateAccMenu, accCalibrationStatus, DYNAMIC);
|
||||
cmsAddMenuEntry(&setupPopupMenuEntries[++menuIndex], "CALIBRATE ACC", OME_Funcall | DYNAMIC, cmsCalibrateAccMenu, accCalibrationStatus);
|
||||
}
|
||||
#endif
|
||||
|
||||
cmsAddMenuEntry(&setupPopupMenuEntries[++menuIndex], "EXIT", OME_Back, NULL, NULL, DYNAMIC);
|
||||
cmsAddMenuEntry(&setupPopupMenuEntries[++menuIndex], "NULL", OME_END, NULL, NULL, 0);
|
||||
cmsAddMenuEntry(&setupPopupMenuEntries[++menuIndex], "EXIT", OME_Back | DYNAMIC, NULL, NULL);
|
||||
cmsAddMenuEntry(&setupPopupMenuEntries[++menuIndex], "NULL", OME_END, NULL, NULL);
|
||||
|
||||
return (menuIndex > 2); // return true if any setup items were added
|
||||
}
|
||||
|
@ -181,17 +181,17 @@ static const void *mainMenuOnEnter(displayPort_t *pDisp)
|
|||
|
||||
static const OSD_Entry menuMainEntries[] =
|
||||
{
|
||||
{"-- MAIN --", OME_Label, NULL, NULL, 0},
|
||||
{"-- MAIN --", OME_Label, NULL, NULL},
|
||||
|
||||
{"PROFILE", OME_Submenu, cmsMenuChange, &cmsx_menuImu, 0},
|
||||
{"FEATURES", OME_Submenu, cmsMenuChange, &cmsx_menuFeatures, 0},
|
||||
{"PROFILE", OME_Submenu, cmsMenuChange, &cmsx_menuImu},
|
||||
{"FEATURES", OME_Submenu, cmsMenuChange, &cmsx_menuFeatures},
|
||||
#ifdef USE_OSD
|
||||
{"OSD", OME_Submenu, cmsMenuChange, &cmsx_menuOsd, 0},
|
||||
{"OSD", OME_Submenu, cmsMenuChange, &cmsx_menuOsd},
|
||||
#endif
|
||||
{"FC&FIRMWARE", OME_Submenu, cmsMenuChange, &cmsx_menuFirmware, 0},
|
||||
{"MISC", OME_Submenu, cmsMenuChange, &cmsx_menuMisc, 0},
|
||||
{"SAVE/EXIT", OME_Funcall, cmsx_SaveExitMenu, NULL, 0},
|
||||
{NULL, OME_END, NULL, NULL, 0},
|
||||
{"FC&FIRMWARE", OME_Submenu, cmsMenuChange, &cmsx_menuFirmware},
|
||||
{"MISC", OME_Submenu, cmsMenuChange, &cmsx_menuMisc},
|
||||
{"SAVE/EXIT", OME_Funcall, cmsx_SaveExitMenu, NULL},
|
||||
{NULL, OME_END, NULL, NULL},
|
||||
};
|
||||
|
||||
CMS_Menu cmsx_menuMain = {
|
||||
|
|
|
@ -73,7 +73,7 @@ static const void *cmsx_menuRcConfirmBack(displayPort_t *pDisp, const OSD_Entry
|
|||
{
|
||||
UNUSED(pDisp);
|
||||
|
||||
if (self && self->type == OME_Back) {
|
||||
if (self && ((self->flags & OSD_MENU_ELEMENT_MASK) == OME_Back)) {
|
||||
return NULL;
|
||||
} else {
|
||||
return MENU_CHAIN_BACK;
|
||||
|
@ -99,20 +99,20 @@ static const void *cmsx_menuRcOnDisplayUpdate(displayPort_t *pDisp, const OSD_En
|
|||
//
|
||||
static const OSD_Entry cmsx_menuRcEntries[] =
|
||||
{
|
||||
{ "-- RC PREV --", OME_Label, NULL, NULL, 0},
|
||||
{ "-- RC PREV --", OME_Label, NULL, NULL},
|
||||
|
||||
{ "ROLL", OME_INT16, NULL, &(OSD_INT16_t){ &rcDataInt[ROLL], 1, 2500, 0 }, DYNAMIC },
|
||||
{ "PITCH", OME_INT16, NULL, &(OSD_INT16_t){ &rcDataInt[PITCH], 1, 2500, 0 }, DYNAMIC },
|
||||
{ "THR", OME_INT16, NULL, &(OSD_INT16_t){ &rcDataInt[THROTTLE], 1, 2500, 0 }, DYNAMIC },
|
||||
{ "YAW", OME_INT16, NULL, &(OSD_INT16_t){ &rcDataInt[YAW], 1, 2500, 0 }, DYNAMIC },
|
||||
{ "ROLL", OME_INT16 | DYNAMIC, NULL, &(OSD_INT16_t){ &rcDataInt[ROLL], 1, 2500, 0 } },
|
||||
{ "PITCH", OME_INT16 | DYNAMIC, NULL, &(OSD_INT16_t){ &rcDataInt[PITCH], 1, 2500, 0 } },
|
||||
{ "THR", OME_INT16 | DYNAMIC, NULL, &(OSD_INT16_t){ &rcDataInt[THROTTLE], 1, 2500, 0 } },
|
||||
{ "YAW", OME_INT16 | DYNAMIC, NULL, &(OSD_INT16_t){ &rcDataInt[YAW], 1, 2500, 0 } },
|
||||
|
||||
{ "AUX1", OME_INT16, NULL, &(OSD_INT16_t){ &rcDataInt[AUX1], 1, 2500, 0 }, DYNAMIC },
|
||||
{ "AUX2", OME_INT16, NULL, &(OSD_INT16_t){ &rcDataInt[AUX2], 1, 2500, 0 }, DYNAMIC },
|
||||
{ "AUX3", OME_INT16, NULL, &(OSD_INT16_t){ &rcDataInt[AUX3], 1, 2500, 0 }, DYNAMIC },
|
||||
{ "AUX4", OME_INT16, NULL, &(OSD_INT16_t){ &rcDataInt[AUX4], 1, 2500, 0 }, DYNAMIC },
|
||||
{ "AUX1", OME_INT16 | DYNAMIC, NULL, &(OSD_INT16_t){ &rcDataInt[AUX1], 1, 2500, 0 } },
|
||||
{ "AUX2", OME_INT16 | DYNAMIC, NULL, &(OSD_INT16_t){ &rcDataInt[AUX2], 1, 2500, 0 } },
|
||||
{ "AUX3", OME_INT16 | DYNAMIC, NULL, &(OSD_INT16_t){ &rcDataInt[AUX3], 1, 2500, 0 } },
|
||||
{ "AUX4", OME_INT16 | DYNAMIC, NULL, &(OSD_INT16_t){ &rcDataInt[AUX4], 1, 2500, 0 } },
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0},
|
||||
{NULL, OME_END, NULL, NULL, 0}
|
||||
{ "BACK", OME_Back, NULL, NULL},
|
||||
{NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
CMS_Menu cmsx_menuRcPreview = {
|
||||
|
@ -155,15 +155,15 @@ static const void *cmsx_menuMiscOnExit(displayPort_t *pDisp, const OSD_Entry *se
|
|||
|
||||
static const OSD_Entry menuMiscEntries[]=
|
||||
{
|
||||
{ "-- MISC --", OME_Label, NULL, NULL, 0 },
|
||||
{ "-- MISC --", OME_Label, NULL, NULL },
|
||||
|
||||
{ "MIN THR", OME_UINT16, NULL, &(OSD_UINT16_t){ &motorConfig_minthrottle, 1000, 2000, 1 }, REBOOT_REQUIRED },
|
||||
{ "DIGITAL IDLE", OME_UINT8, NULL, &(OSD_UINT8_t) { &motorConfig_digitalIdleOffsetValue, 0, 200, 1 }, REBOOT_REQUIRED },
|
||||
{ "FPV CAM ANGLE", OME_UINT8, NULL, &(OSD_UINT8_t) { &rxConfig_fpvCamAngleDegrees, 0, 90, 1 }, 0 },
|
||||
{ "RC PREV", OME_Submenu, cmsMenuChange, &cmsx_menuRcPreview, 0},
|
||||
{ "MIN THR", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &motorConfig_minthrottle, 1000, 2000, 1 } },
|
||||
{ "DIGITAL IDLE", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t) { &motorConfig_digitalIdleOffsetValue, 0, 200, 1 } },
|
||||
{ "FPV CAM ANGLE", OME_UINT8, NULL, &(OSD_UINT8_t) { &rxConfig_fpvCamAngleDegrees, 0, 90, 1 } },
|
||||
{ "RC PREV", OME_Submenu, cmsMenuChange, &cmsx_menuRcPreview},
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0},
|
||||
{ NULL, OME_END, NULL, NULL, 0}
|
||||
{ "BACK", OME_Back, NULL, NULL},
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
CMS_Menu cmsx_menuMisc = {
|
||||
|
|
|
@ -76,97 +76,97 @@ static const void *menuOsdActiveElemsOnExit(displayPort_t *pDisp, const OSD_Entr
|
|||
|
||||
const OSD_Entry menuOsdActiveElemsEntries[] =
|
||||
{
|
||||
{"--- ACTIV ELEM ---", OME_Label, NULL, NULL, 0},
|
||||
{"RSSI", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_RSSI_VALUE], DYNAMIC},
|
||||
{"--- ACTIV ELEM ---", OME_Label, NULL, NULL},
|
||||
{"RSSI", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_RSSI_VALUE]},
|
||||
#ifdef USE_RX_RSSI_DBM
|
||||
{"RSSI DBM", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_RSSI_DBM_VALUE], DYNAMIC},
|
||||
{"RSSI DBM", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_RSSI_DBM_VALUE]},
|
||||
#endif
|
||||
{"BATTERY VOLTAGE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_MAIN_BATT_VOLTAGE], DYNAMIC},
|
||||
{"BATTERY USAGE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_MAIN_BATT_USAGE], DYNAMIC},
|
||||
{"AVG CELL VOLTAGE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_AVG_CELL_VOLTAGE], DYNAMIC},
|
||||
{"BATTERY VOLTAGE", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_MAIN_BATT_VOLTAGE]},
|
||||
{"BATTERY USAGE", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_MAIN_BATT_USAGE]},
|
||||
{"AVG CELL VOLTAGE", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_AVG_CELL_VOLTAGE]},
|
||||
#ifdef USE_GPS
|
||||
{"BATTERY EFFICIENCY", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_EFFICIENCY], DYNAMIC},
|
||||
{"BATTERY EFFICIENCY", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_EFFICIENCY]},
|
||||
#endif // GPS
|
||||
{"CROSSHAIRS", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_CROSSHAIRS], DYNAMIC},
|
||||
{"HORIZON", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ARTIFICIAL_HORIZON], DYNAMIC},
|
||||
{"HORIZON SIDEBARS", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_HORIZON_SIDEBARS], DYNAMIC},
|
||||
{"UP/DOWN REFERENCE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_UP_DOWN_REFERENCE], DYNAMIC},
|
||||
{"TIMER 1", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ITEM_TIMER_1], DYNAMIC},
|
||||
{"TIMER 2", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ITEM_TIMER_2], DYNAMIC},
|
||||
{"REMAINING TIME ESTIMATE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_REMAINING_TIME_ESTIMATE], DYNAMIC},
|
||||
{"CROSSHAIRS", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_CROSSHAIRS]},
|
||||
{"HORIZON", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_ARTIFICIAL_HORIZON]},
|
||||
{"HORIZON SIDEBARS", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_HORIZON_SIDEBARS]},
|
||||
{"UP/DOWN REFERENCE", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_UP_DOWN_REFERENCE]},
|
||||
{"TIMER 1", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_ITEM_TIMER_1]},
|
||||
{"TIMER 2", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_ITEM_TIMER_2]},
|
||||
{"REMAINING TIME ESTIMATE", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_REMAINING_TIME_ESTIMATE]},
|
||||
#ifdef USE_RTC_TIME
|
||||
{"RTC DATETIME", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_RTC_DATETIME], DYNAMIC},
|
||||
{"RTC DATETIME", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_RTC_DATETIME]},
|
||||
#endif
|
||||
#ifdef USE_OSD_ADJUSTMENTS
|
||||
{"ADJUSTMENT RANGE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ADJUSTMENT_RANGE], DYNAMIC},
|
||||
{"ADJUSTMENT RANGE", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_ADJUSTMENT_RANGE]},
|
||||
#endif
|
||||
#ifdef USE_ADC_INTERNAL
|
||||
{"CORE TEMPERATURE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_CORE_TEMPERATURE], DYNAMIC},
|
||||
{"CORE TEMPERATURE", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_CORE_TEMPERATURE]},
|
||||
#endif
|
||||
{"ANTI GRAVITY", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ANTI_GRAVITY], DYNAMIC},
|
||||
{"FLY MODE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_FLYMODE], DYNAMIC},
|
||||
{"NAME", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_CRAFT_NAME], DYNAMIC},
|
||||
{"THROTTLE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_THROTTLE_POS], DYNAMIC},
|
||||
{"ANTI GRAVITY", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_ANTI_GRAVITY]},
|
||||
{"FLY MODE", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_FLYMODE]},
|
||||
{"NAME", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_CRAFT_NAME]},
|
||||
{"THROTTLE", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_THROTTLE_POS]},
|
||||
#ifdef USE_VTX_CONTROL
|
||||
{"VTX CHAN", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_VTX_CHANNEL], DYNAMIC},
|
||||
{"VTX CHAN", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_VTX_CHANNEL]},
|
||||
#endif // VTX
|
||||
{"CURRENT (A)", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_CURRENT_DRAW], DYNAMIC},
|
||||
{"USED MAH", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_MAH_DRAWN], DYNAMIC},
|
||||
{"CURRENT (A)", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_CURRENT_DRAW]},
|
||||
{"USED MAH", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_MAH_DRAWN]},
|
||||
#ifdef USE_GPS
|
||||
{"GPS SPEED", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_GPS_SPEED], DYNAMIC},
|
||||
{"GPS SATS", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_GPS_SATS], DYNAMIC},
|
||||
{"GPS LAT", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_GPS_LAT], DYNAMIC},
|
||||
{"GPS LON", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_GPS_LON], DYNAMIC},
|
||||
{"HOME DIR", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_HOME_DIR], DYNAMIC},
|
||||
{"HOME DIST", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_HOME_DIST], DYNAMIC},
|
||||
{"FLIGHT DIST", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_FLIGHT_DIST], DYNAMIC},
|
||||
{"GPS SPEED", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_GPS_SPEED]},
|
||||
{"GPS SATS", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_GPS_SATS]},
|
||||
{"GPS LAT", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_GPS_LAT]},
|
||||
{"GPS LON", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_GPS_LON]},
|
||||
{"HOME DIR", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_HOME_DIR]},
|
||||
{"HOME DIST", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_HOME_DIST]},
|
||||
{"FLIGHT DIST", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_FLIGHT_DIST]},
|
||||
#endif // GPS
|
||||
{"COMPASS BAR", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_COMPASS_BAR], DYNAMIC},
|
||||
{"COMPASS BAR", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_COMPASS_BAR]},
|
||||
#ifdef USE_ESC_SENSOR
|
||||
{"ESC TEMPERATURE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ESC_TMP], DYNAMIC},
|
||||
{"ESC RPM", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ESC_RPM], DYNAMIC},
|
||||
{"ESC TEMPERATURE", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_ESC_TMP]},
|
||||
{"ESC RPM", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_ESC_RPM]},
|
||||
#endif
|
||||
{"ALTITUDE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ALTITUDE], DYNAMIC},
|
||||
{"POWER", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_POWER], DYNAMIC},
|
||||
{"ROLL PID", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ROLL_PIDS], DYNAMIC},
|
||||
{"PITCH PID", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_PITCH_PIDS], DYNAMIC},
|
||||
{"YAW PID", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_YAW_PIDS], DYNAMIC},
|
||||
{"PROFILES", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_PIDRATE_PROFILE], DYNAMIC},
|
||||
{"ALTITUDE", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_ALTITUDE]},
|
||||
{"POWER", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_POWER]},
|
||||
{"ROLL PID", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_ROLL_PIDS]},
|
||||
{"PITCH PID", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_PITCH_PIDS]},
|
||||
{"YAW PID", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_YAW_PIDS]},
|
||||
{"PROFILES", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_PIDRATE_PROFILE]},
|
||||
#ifdef USE_PROFILE_NAMES
|
||||
{"PID PROFILE NAME", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_PID_PROFILE_NAME], DYNAMIC},
|
||||
{"RATE PROFILE NAME", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_RATE_PROFILE_NAME], DYNAMIC},
|
||||
{"PID PROFILE NAME", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_PID_PROFILE_NAME]},
|
||||
{"RATE PROFILE NAME", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_RATE_PROFILE_NAME]},
|
||||
#endif
|
||||
#ifdef USE_OSD_PROFILES
|
||||
{"OSD PROFILE NAME", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_PROFILE_NAME], DYNAMIC},
|
||||
{"OSD PROFILE NAME", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_PROFILE_NAME]},
|
||||
#endif
|
||||
{"DEBUG", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_DEBUG], DYNAMIC},
|
||||
{"WARNINGS", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_WARNINGS], DYNAMIC},
|
||||
{"DISARMED", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_DISARMED], DYNAMIC},
|
||||
{"PIT ANG", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_PITCH_ANGLE], DYNAMIC},
|
||||
{"ROL ANG", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ROLL_ANGLE], DYNAMIC},
|
||||
{"HEADING", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_NUMERICAL_HEADING], DYNAMIC},
|
||||
{"DEBUG", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_DEBUG]},
|
||||
{"WARNINGS", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_WARNINGS]},
|
||||
{"DISARMED", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_DISARMED]},
|
||||
{"PIT ANG", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_PITCH_ANGLE]},
|
||||
{"ROL ANG", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_ROLL_ANGLE]},
|
||||
{"HEADING", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_NUMERICAL_HEADING]},
|
||||
#ifdef USE_VARIO
|
||||
{"VARIO", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_NUMERICAL_VARIO], DYNAMIC},
|
||||
{"VARIO", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_NUMERICAL_VARIO]},
|
||||
#endif
|
||||
{"G-FORCE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_G_FORCE], DYNAMIC},
|
||||
{"MOTOR DIAGNOSTIC", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_MOTOR_DIAG], DYNAMIC},
|
||||
{"G-FORCE", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_G_FORCE]},
|
||||
{"MOTOR DIAGNOSTIC", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_MOTOR_DIAG]},
|
||||
#ifdef USE_BLACKBOX
|
||||
{"LOG STATUS", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_LOG_STATUS], DYNAMIC},
|
||||
{"LOG STATUS", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_LOG_STATUS]},
|
||||
#endif
|
||||
{"FLIP ARROW", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_FLIP_ARROW], DYNAMIC},
|
||||
{"FLIP ARROW", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_FLIP_ARROW]},
|
||||
#ifdef USE_RX_LINK_QUALITY_INFO
|
||||
{"LINK QUALITY", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_LINK_QUALITY], DYNAMIC},
|
||||
{"LINK QUALITY", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_LINK_QUALITY]},
|
||||
#endif
|
||||
#ifdef USE_OSD_STICK_OVERLAY
|
||||
{"STICK OVERLAY LEFT", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_STICK_OVERLAY_LEFT], DYNAMIC},
|
||||
{"STICK OVERLAY RIGHT",OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_STICK_OVERLAY_RIGHT], DYNAMIC},
|
||||
{"STICK OVERLAY LEFT", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_STICK_OVERLAY_LEFT]},
|
||||
{"STICK OVERLAY RIGHT",OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_STICK_OVERLAY_RIGHT]},
|
||||
#endif
|
||||
{"DISPLAY NAME", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_DISPLAY_NAME], DYNAMIC},
|
||||
{"RC CHANNELS", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_RC_CHANNELS], DYNAMIC},
|
||||
{"CAMERA FRAME", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_CAMERA_FRAME], DYNAMIC},
|
||||
{"TOTAL FLIGHTS", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_TOTAL_FLIGHTS], DYNAMIC},
|
||||
{"BACK", OME_Back, NULL, NULL, 0},
|
||||
{NULL, OME_END, NULL, NULL, 0}
|
||||
{"DISPLAY NAME", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_DISPLAY_NAME]},
|
||||
{"RC CHANNELS", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_RC_CHANNELS]},
|
||||
{"CAMERA FRAME", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_CAMERA_FRAME]},
|
||||
{"TOTAL FLIGHTS", OME_VISIBLE | DYNAMIC, NULL, &osdConfig_item_pos[OSD_TOTAL_FLIGHTS]},
|
||||
{"BACK", OME_Back, NULL, NULL},
|
||||
{NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
static CMS_Menu menuOsdActiveElems = {
|
||||
|
@ -224,17 +224,17 @@ static const void *menuAlarmsOnExit(displayPort_t *pDisp, const OSD_Entry *self)
|
|||
|
||||
const OSD_Entry menuAlarmsEntries[] =
|
||||
{
|
||||
{"--- ALARMS ---", OME_Label, NULL, NULL, 0},
|
||||
{"RSSI", OME_UINT8, NULL, &(OSD_UINT8_t){&osdConfig_rssi_alarm, 5, 90, 5}, 0},
|
||||
{"LINK QUALITY", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_link_quality_alarm, 5, 300, 5}, 0},
|
||||
{"RSSI DBM", OME_INT16, NULL, &(OSD_INT16_t){&osdConfig_rssi_dbm_alarm, CRSF_RSSI_MIN, CRSF_SNR_MAX, 5}, 0},
|
||||
{"MAIN BAT", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_cap_alarm, 50, 30000, 50}, 0},
|
||||
{"MAX ALT", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_alt_alarm, 1, 200, 1}, 0},
|
||||
{"MAX DISTANCE", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_distance_alarm, 0, UINT16_MAX, 10}, 0},
|
||||
{"VBAT WARN DUR", OME_UINT8, NULL, &(OSD_UINT8_t){ &batteryConfig_vbatDurationForWarning, 0, 200, 1 }, 0 },
|
||||
{"VBAT CRIT DUR", OME_UINT8, NULL, &(OSD_UINT8_t){ &batteryConfig_vbatDurationForCritical, 0, 200, 1 }, 0 },
|
||||
{"BACK", OME_Back, NULL, NULL, 0},
|
||||
{NULL, OME_END, NULL, NULL, 0}
|
||||
{"--- ALARMS ---", OME_Label, NULL, NULL},
|
||||
{"RSSI", OME_UINT8, NULL, &(OSD_UINT8_t){&osdConfig_rssi_alarm, 5, 90, 5}},
|
||||
{"LINK QUALITY", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_link_quality_alarm, 5, 300, 5}},
|
||||
{"RSSI DBM", OME_INT16, NULL, &(OSD_INT16_t){&osdConfig_rssi_dbm_alarm, CRSF_RSSI_MIN, CRSF_SNR_MAX, 5}},
|
||||
{"MAIN BAT", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_cap_alarm, 50, 30000, 50}},
|
||||
{"MAX ALT", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_alt_alarm, 1, 200, 1}},
|
||||
{"MAX DISTANCE", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_distance_alarm, 0, UINT16_MAX, 10}},
|
||||
{"VBAT WARN DUR", OME_UINT8, NULL, &(OSD_UINT8_t){ &batteryConfig_vbatDurationForWarning, 0, 200, 1 } },
|
||||
{"VBAT CRIT DUR", OME_UINT8, NULL, &(OSD_UINT8_t){ &batteryConfig_vbatDurationForCritical, 0, 200, 1 } },
|
||||
{"BACK", OME_Back, NULL, NULL},
|
||||
{NULL, OME_END, NULL, NULL,}
|
||||
};
|
||||
|
||||
static CMS_Menu menuAlarms = {
|
||||
|
@ -282,15 +282,15 @@ static const char * osdTimerPrecisionNames[] = {"SCND", "HDTH"};
|
|||
|
||||
const OSD_Entry menuTimersEntries[] =
|
||||
{
|
||||
{"--- TIMERS ---", OME_Label, NULL, NULL, 0},
|
||||
{"1 SRC", OME_TAB, NULL, &(OSD_TAB_t){&timerSource[OSD_TIMER_1], OSD_TIMER_SRC_COUNT - 1, osdTimerSourceNames}, 0 },
|
||||
{"1 PREC", OME_TAB, NULL, &(OSD_TAB_t){&timerPrecision[OSD_TIMER_1], OSD_TIMER_PREC_COUNT - 1, osdTimerPrecisionNames}, 0},
|
||||
{"1 ALARM", OME_UINT8, NULL, &(OSD_UINT8_t){&timerAlarm[OSD_TIMER_1], 0, 0xFF, 1}, 0},
|
||||
{"2 SRC", OME_TAB, NULL, &(OSD_TAB_t){&timerSource[OSD_TIMER_2], OSD_TIMER_SRC_COUNT - 1, osdTimerSourceNames}, 0 },
|
||||
{"2 PREC", OME_TAB, NULL, &(OSD_TAB_t){&timerPrecision[OSD_TIMER_2], OSD_TIMER_PREC_COUNT - 1, osdTimerPrecisionNames}, 0},
|
||||
{"2 ALARM", OME_UINT8, NULL, &(OSD_UINT8_t){&timerAlarm[OSD_TIMER_2], 0, 0xFF, 1}, 0},
|
||||
{"BACK", OME_Back, NULL, NULL, 0},
|
||||
{NULL, OME_END, NULL, NULL, 0}
|
||||
{"--- TIMERS ---", OME_Label, NULL, NULL},
|
||||
{"1 SRC", OME_TAB, NULL, &(OSD_TAB_t){&timerSource[OSD_TIMER_1], OSD_TIMER_SRC_COUNT - 1, osdTimerSourceNames} },
|
||||
{"1 PREC", OME_TAB, NULL, &(OSD_TAB_t){&timerPrecision[OSD_TIMER_1], OSD_TIMER_PREC_COUNT - 1, osdTimerPrecisionNames}},
|
||||
{"1 ALARM", OME_UINT8, NULL, &(OSD_UINT8_t){&timerAlarm[OSD_TIMER_1], 0, 0xFF, 1}},
|
||||
{"2 SRC", OME_TAB, NULL, &(OSD_TAB_t){&timerSource[OSD_TIMER_2], OSD_TIMER_SRC_COUNT - 1, osdTimerSourceNames} },
|
||||
{"2 PREC", OME_TAB, NULL, &(OSD_TAB_t){&timerPrecision[OSD_TIMER_2], OSD_TIMER_PREC_COUNT - 1, osdTimerPrecisionNames}},
|
||||
{"2 ALARM", OME_UINT8, NULL, &(OSD_UINT8_t){&timerAlarm[OSD_TIMER_2], 0, 0xFF, 1}},
|
||||
{"BACK", OME_Back, NULL, NULL},
|
||||
{NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
static CMS_Menu menuTimers = {
|
||||
|
@ -372,23 +372,23 @@ static const void *cmsx_osdBackgroundUpdate(displayPort_t *pDisp, const void *se
|
|||
|
||||
const OSD_Entry cmsx_menuOsdEntries[] =
|
||||
{
|
||||
{"---OSD---", OME_Label, NULL, NULL, 0},
|
||||
{"---OSD---", OME_Label, NULL, NULL},
|
||||
#ifdef USE_OSD_PROFILES
|
||||
{"OSD PROFILE", OME_UINT8, NULL, &(OSD_UINT8_t){&osdConfig_osdProfileIndex, 1, 3, 1}, 0},
|
||||
{"OSD PROFILE", OME_UINT8, NULL, &(OSD_UINT8_t){&osdConfig_osdProfileIndex, 1, 3, 1}},
|
||||
#endif
|
||||
#ifdef USE_EXTENDED_CMS_MENUS
|
||||
{"ACTIVE ELEM", OME_Submenu, cmsMenuChange, &menuOsdActiveElems, 0},
|
||||
{"TIMERS", OME_Submenu, cmsMenuChange, &menuTimers, 0},
|
||||
{"ALARMS", OME_Submenu, cmsMenuChange, &menuAlarms, 0},
|
||||
{"ACTIVE ELEM", OME_Submenu, cmsMenuChange, &menuOsdActiveElems},
|
||||
{"TIMERS", OME_Submenu, cmsMenuChange, &menuTimers},
|
||||
{"ALARMS", OME_Submenu, cmsMenuChange, &menuAlarms},
|
||||
#endif
|
||||
#ifdef USE_MAX7456
|
||||
{"INVERT", OME_Bool, cmsx_max7456Update, &displayPortProfileMax7456_invert, 0},
|
||||
{"BRT BLACK", OME_UINT8, cmsx_max7456Update, &(OSD_UINT8_t){&displayPortProfileMax7456_blackBrightness, 0, 3, 1}, 0},
|
||||
{"BRT WHITE", OME_UINT8, cmsx_max7456Update, &(OSD_UINT8_t){&displayPortProfileMax7456_whiteBrightness, 0, 3, 1}, 0},
|
||||
{"INVERT", OME_Bool, cmsx_max7456Update, &displayPortProfileMax7456_invert},
|
||||
{"BRT BLACK", OME_UINT8, cmsx_max7456Update, &(OSD_UINT8_t){&displayPortProfileMax7456_blackBrightness, 0, 3, 1}},
|
||||
{"BRT WHITE", OME_UINT8, cmsx_max7456Update, &(OSD_UINT8_t){&displayPortProfileMax7456_whiteBrightness, 0, 3, 1}},
|
||||
#endif
|
||||
{"BACKGROUND",OME_TAB, cmsx_osdBackgroundUpdate, &(OSD_TAB_t){&osdMenuBackgroundType, DISPLAY_BACKGROUND_COUNT - 1, lookupTableCMSMenuBackgroundType}, 0},
|
||||
{"BACK", OME_Back, NULL, NULL, 0},
|
||||
{NULL, OME_END, NULL, NULL, 0}
|
||||
{"BACKGROUND",OME_TAB, cmsx_osdBackgroundUpdate, &(OSD_TAB_t){&osdMenuBackgroundType, DISPLAY_BACKGROUND_COUNT - 1, lookupTableCMSMenuBackgroundType}},
|
||||
{"BACK", OME_Back, NULL, NULL},
|
||||
{NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
CMS_Menu cmsx_menuOsd = {
|
||||
|
|
|
@ -81,16 +81,16 @@ static const void *cmsx_ResetStats(displayPort_t *pDisplay, const void *ptr)
|
|||
|
||||
static const OSD_Entry cmsx_menuPersistentStatsEntries[] =
|
||||
{
|
||||
{"-- PERSISTENT STATS --", OME_Label, NULL, NULL, 0},
|
||||
{"FLIGHTS", OME_UINT32, NULL, &(OSD_UINT32_t){ &stats_total_flights, 0, UINT32_MAX, 1}, 0},
|
||||
{"TIME(sec)", OME_UINT32, NULL, &(OSD_UINT32_t){ &stats_total_time_s, 0, UINT32_MAX, 1}, 0},
|
||||
{"DIST(m)", OME_UINT32, NULL, &(OSD_UINT32_t){ &stats_total_dist_m, 0, UINT32_MAX, 1}, 0},
|
||||
{"RESET STATS", OME_Funcall, cmsx_ResetStats, NULL, 0},
|
||||
{"--- SETTINGS ---", OME_Label, NULL, NULL, 0},
|
||||
{"MIN ARMED TIME(sec)", OME_INT8, NULL, &(OSD_INT8_t){ &stats_min_armed_time_s, -1, INT8_MAX, 1}, 0},
|
||||
{"-- PERSISTENT STATS --", OME_Label, NULL, NULL},
|
||||
{"FLIGHTS", OME_UINT32, NULL, &(OSD_UINT32_t){ &stats_total_flights, 0, UINT32_MAX, 1}},
|
||||
{"TIME(sec)", OME_UINT32, NULL, &(OSD_UINT32_t){ &stats_total_time_s, 0, UINT32_MAX, 1}},
|
||||
{"DIST(m)", OME_UINT32, NULL, &(OSD_UINT32_t){ &stats_total_dist_m, 0, UINT32_MAX, 1}},
|
||||
{"RESET STATS", OME_Funcall, cmsx_ResetStats, NULL},
|
||||
{"--- SETTINGS ---", OME_Label, NULL, NULL},
|
||||
{"MIN ARMED TIME(sec)", OME_INT8, NULL, &(OSD_INT8_t){ &stats_min_armed_time_s, -1, INT8_MAX, 1}},
|
||||
|
||||
{"BACK", OME_Back, NULL, NULL, 0},
|
||||
{ NULL, OME_END, NULL, NULL, 0}
|
||||
{"BACK", OME_Back, NULL, NULL},
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
CMS_Menu cmsx_menuPersistentStats = {
|
||||
|
|
|
@ -107,27 +107,27 @@ static const void *cmsx_Power_onExit(displayPort_t *pDisp, const OSD_Entry *self
|
|||
|
||||
static const OSD_Entry cmsx_menuPowerEntries[] =
|
||||
{
|
||||
{ "-- POWER --", OME_Label, NULL, NULL, 0},
|
||||
{ "-- POWER --", OME_Label, NULL, NULL},
|
||||
|
||||
{ "V METER", OME_TAB, NULL, &(OSD_TAB_t){ &batteryConfig_voltageMeterSource, VOLTAGE_METER_COUNT - 1, voltageMeterSourceNames }, REBOOT_REQUIRED },
|
||||
{ "I METER", OME_TAB, NULL, &(OSD_TAB_t){ &batteryConfig_currentMeterSource, CURRENT_METER_COUNT - 1, currentMeterSourceNames }, REBOOT_REQUIRED },
|
||||
{ "V METER", OME_TAB | REBOOT_REQUIRED, NULL, &(OSD_TAB_t){ &batteryConfig_voltageMeterSource, VOLTAGE_METER_COUNT - 1, voltageMeterSourceNames } },
|
||||
{ "I METER", OME_TAB | REBOOT_REQUIRED, NULL, &(OSD_TAB_t){ &batteryConfig_currentMeterSource, CURRENT_METER_COUNT - 1, currentMeterSourceNames } },
|
||||
|
||||
{ "VBAT CLMIN", OME_UINT16, NULL, &(OSD_UINT16_t) { &batteryConfig_vbatmincellvoltage, VBAT_CELL_VOTAGE_RANGE_MIN, VBAT_CELL_VOTAGE_RANGE_MAX, 1 }, 0 },
|
||||
{ "VBAT CLMAX", OME_UINT16, NULL, &(OSD_UINT16_t) { &batteryConfig_vbatmaxcellvoltage, VBAT_CELL_VOTAGE_RANGE_MIN, VBAT_CELL_VOTAGE_RANGE_MAX, 1 }, 0 },
|
||||
{ "VBAT CLWARN", OME_UINT16, NULL, &(OSD_UINT16_t) { &batteryConfig_vbatwarningcellvoltage, VBAT_CELL_VOTAGE_RANGE_MIN, VBAT_CELL_VOTAGE_RANGE_MAX, 1 }, 0 },
|
||||
{ "VBAT CLMIN", OME_UINT16, NULL, &(OSD_UINT16_t) { &batteryConfig_vbatmincellvoltage, VBAT_CELL_VOTAGE_RANGE_MIN, VBAT_CELL_VOTAGE_RANGE_MAX, 1 } },
|
||||
{ "VBAT CLMAX", OME_UINT16, NULL, &(OSD_UINT16_t) { &batteryConfig_vbatmaxcellvoltage, VBAT_CELL_VOTAGE_RANGE_MIN, VBAT_CELL_VOTAGE_RANGE_MAX, 1 } },
|
||||
{ "VBAT CLWARN", OME_UINT16, NULL, &(OSD_UINT16_t) { &batteryConfig_vbatwarningcellvoltage, VBAT_CELL_VOTAGE_RANGE_MIN, VBAT_CELL_VOTAGE_RANGE_MAX, 1 } },
|
||||
|
||||
{ "VBAT SCALE", OME_UINT8, NULL, &(OSD_UINT8_t){ &voltageSensorADCConfig_vbatscale, VBAT_SCALE_MIN, VBAT_SCALE_MAX, 1 }, 0 },
|
||||
{ "VBAT SCALE", OME_UINT8, NULL, &(OSD_UINT8_t){ &voltageSensorADCConfig_vbatscale, VBAT_SCALE_MIN, VBAT_SCALE_MAX, 1 } },
|
||||
|
||||
{ "IBAT SCALE", OME_INT16, NULL, &(OSD_INT16_t){ ¤tSensorADCConfig_scale, -16000, 16000, 5 }, 0 },
|
||||
{ "IBAT OFFSET", OME_INT16, NULL, &(OSD_INT16_t){ ¤tSensorADCConfig_offset, -32000, 32000, 5 }, 0 },
|
||||
{ "IBAT SCALE", OME_INT16, NULL, &(OSD_INT16_t){ ¤tSensorADCConfig_scale, -16000, 16000, 5 } },
|
||||
{ "IBAT OFFSET", OME_INT16, NULL, &(OSD_INT16_t){ ¤tSensorADCConfig_offset, -32000, 32000, 5 } },
|
||||
|
||||
#ifdef USE_VIRTUAL_CURRENT_METER
|
||||
{ "IBAT VIRT SCALE", OME_INT16, NULL, &(OSD_INT16_t){ ¤tSensorVirtualConfig_scale, -16000, 16000, 5 }, 0 },
|
||||
{ "IBAT VIRT OFFSET", OME_UINT16, NULL, &(OSD_UINT16_t){ ¤tSensorVirtualConfig_offset, 0, 16000, 5 }, 0 },
|
||||
{ "IBAT VIRT SCALE", OME_INT16, NULL, &(OSD_INT16_t){ ¤tSensorVirtualConfig_scale, -16000, 16000, 5 } },
|
||||
{ "IBAT VIRT OFFSET", OME_UINT16, NULL, &(OSD_UINT16_t){ ¤tSensorVirtualConfig_offset, 0, 16000, 5 } },
|
||||
#endif
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
CMS_Menu cmsx_menuPower = {
|
||||
|
|
|
@ -36,12 +36,12 @@
|
|||
|
||||
static const OSD_Entry cmsx_menuSaveExitEntries[] =
|
||||
{
|
||||
{ "-- SAVE/EXIT --", OME_Label, NULL, NULL, 0},
|
||||
{ "EXIT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_EXIT, 0},
|
||||
{ "SAVE&EXIT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_POPUP_SAVE, 0},
|
||||
{ "SAVE&REBOOT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_POPUP_SAVEREBOOT, 0},
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "-- SAVE/EXIT --", OME_Label, NULL, NULL},
|
||||
{ "EXIT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_EXIT},
|
||||
{ "SAVE&EXIT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_POPUP_SAVE},
|
||||
{ "SAVE&REBOOT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_POPUP_SAVEREBOOT},
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
static CMS_Menu cmsx_menuSaveExit = {
|
||||
|
@ -57,11 +57,11 @@ static CMS_Menu cmsx_menuSaveExit = {
|
|||
|
||||
static const OSD_Entry cmsx_menuSaveExitRebootEntries[] =
|
||||
{
|
||||
{ "-- SAVE/EXIT (REBOOT REQD)", OME_Label, NULL, NULL, 0},
|
||||
{ "EXIT&REBOOT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_POPUP_EXITREBOOT, 0},
|
||||
{ "SAVE&REBOOT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_POPUP_SAVEREBOOT, 0},
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "-- SAVE/EXIT (REBOOT REQD)", OME_Label, NULL, NULL},
|
||||
{ "EXIT&REBOOT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_POPUP_EXITREBOOT},
|
||||
{ "SAVE&REBOOT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_POPUP_SAVEREBOOT},
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
static CMS_Menu cmsx_menuSaveExitReboot = {
|
||||
|
|
|
@ -68,11 +68,11 @@ static const void *setStatusMessage(displayPort_t *pDisp)
|
|||
|
||||
static const OSD_Entry vtxErrorMenuEntries[] =
|
||||
{
|
||||
{ "", OME_Label, NULL, statusLine1, DYNAMIC },
|
||||
{ "", OME_Label, NULL, statusLine2, DYNAMIC },
|
||||
{ "", OME_Label, NULL, NULL, 0 },
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "", OME_Label | DYNAMIC, NULL, statusLine1 },
|
||||
{ "", OME_Label | DYNAMIC, NULL, statusLine2 },
|
||||
{ "", OME_Label, NULL, NULL },
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL }
|
||||
};
|
||||
|
||||
static CMS_Menu cmsx_menuVtxError = {
|
||||
|
|
|
@ -151,13 +151,13 @@ static const void *cmsx_Vtx_onPitChange(displayPort_t *pDisp, const void *self)
|
|||
}
|
||||
|
||||
static const OSD_Entry cmsx_menuVtxEntries[] = {
|
||||
{"--- VTX ---", OME_Label, NULL, NULL, 0},
|
||||
{"BAND", OME_TAB, cmsx_Vtx_onBandChange, &entryVtxBand, 0},
|
||||
{"CHANNEL", OME_TAB, cmsx_Vtx_onChanChange, &entryVtxChannel, 0},
|
||||
{"POWER", OME_TAB, cmsx_Vtx_onPowerChange, &entryVtxPower, 0},
|
||||
{"PIT", OME_TAB, cmsx_Vtx_onPitChange, &entryVtxPit, 0},
|
||||
{"BACK", OME_Back, NULL, NULL, 0},
|
||||
{NULL, OME_END, NULL, NULL, 0}
|
||||
{"--- VTX ---", OME_Label, NULL, NULL},
|
||||
{"BAND", OME_TAB, cmsx_Vtx_onBandChange, &entryVtxBand},
|
||||
{"CHANNEL", OME_TAB, cmsx_Vtx_onChanChange, &entryVtxChannel},
|
||||
{"POWER", OME_TAB, cmsx_Vtx_onPowerChange, &entryVtxPower},
|
||||
{"PIT", OME_TAB, cmsx_Vtx_onPitChange, &entryVtxPit},
|
||||
{"BACK", OME_Back, NULL, NULL},
|
||||
{NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
CMS_Menu cmsx_menuVtxRTC6705 = {
|
||||
|
|
|
@ -396,17 +396,17 @@ static const char * const saCmsDeviceStatusNames[] = {
|
|||
static OSD_TAB_t saCmsEntOnline = { &saCmsDeviceStatus, 3, saCmsDeviceStatusNames };
|
||||
|
||||
static const OSD_Entry saCmsMenuStatsEntries[] = {
|
||||
{ "- SA STATS -", OME_Label, NULL, NULL, 0 },
|
||||
{ "STATUS", OME_TAB, NULL, &saCmsEntOnline, DYNAMIC },
|
||||
{ "BAUDRATE", OME_UINT16, NULL, &(OSD_UINT16_t){ &sa_smartbaud, 0, 0, 0 }, DYNAMIC },
|
||||
{ "SENT", OME_UINT16, NULL, &(OSD_UINT16_t){ &saStat.pktsent, 0, 0, 0 }, DYNAMIC },
|
||||
{ "RCVD", OME_UINT16, NULL, &(OSD_UINT16_t){ &saStat.pktrcvd, 0, 0, 0 }, DYNAMIC },
|
||||
{ "BADPRE", OME_UINT16, NULL, &(OSD_UINT16_t){ &saStat.badpre, 0, 0, 0 }, DYNAMIC },
|
||||
{ "BADLEN", OME_UINT16, NULL, &(OSD_UINT16_t){ &saStat.badlen, 0, 0, 0 }, DYNAMIC },
|
||||
{ "CRCERR", OME_UINT16, NULL, &(OSD_UINT16_t){ &saStat.crc, 0, 0, 0 }, DYNAMIC },
|
||||
{ "OOOERR", OME_UINT16, NULL, &(OSD_UINT16_t){ &saStat.ooopresp, 0, 0, 0 }, DYNAMIC },
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "- SA STATS -", OME_Label, NULL, NULL },
|
||||
{ "STATUS", OME_TAB | DYNAMIC, NULL, &saCmsEntOnline },
|
||||
{ "BAUDRATE", OME_UINT16 | DYNAMIC, NULL, &(OSD_UINT16_t){ &sa_smartbaud, 0, 0, 0 } },
|
||||
{ "SENT", OME_UINT16 | DYNAMIC, NULL, &(OSD_UINT16_t){ &saStat.pktsent, 0, 0, 0 } },
|
||||
{ "RCVD", OME_UINT16 | DYNAMIC, NULL, &(OSD_UINT16_t){ &saStat.pktrcvd, 0, 0, 0 } },
|
||||
{ "BADPRE", OME_UINT16 | DYNAMIC, NULL, &(OSD_UINT16_t){ &saStat.badpre, 0, 0, 0 } },
|
||||
{ "BADLEN", OME_UINT16 | DYNAMIC, NULL, &(OSD_UINT16_t){ &saStat.badlen, 0, 0, 0 } },
|
||||
{ "CRCERR", OME_UINT16 | DYNAMIC, NULL, &(OSD_UINT16_t){ &saStat.crc, 0, 0, 0 } },
|
||||
{ "OOOERR", OME_UINT16 | DYNAMIC, NULL, &(OSD_UINT16_t){ &saStat.ooopresp, 0, 0, 0 } },
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL }
|
||||
};
|
||||
|
||||
static CMS_Menu saCmsMenuStats = {
|
||||
|
@ -606,14 +606,14 @@ static const void *saCmsConfigUserFreq(displayPort_t *pDisp, const void *self)
|
|||
}
|
||||
|
||||
static const OSD_Entry saCmsMenuPORFreqEntries[] = {
|
||||
{ "- POR FREQ -", OME_Label, NULL, NULL, 0 },
|
||||
{ "- POR FREQ -", OME_Label, NULL, NULL },
|
||||
|
||||
{ "CUR FREQ", OME_UINT16, NULL, &(OSD_UINT16_t){ &saCmsORFreq, 5000, 5999, 0 }, DYNAMIC },
|
||||
{ "NEW FREQ", OME_UINT16, NULL, &(OSD_UINT16_t){ &saCmsORFreqNew, 5000, 5999, 1 }, 0 },
|
||||
{ "SET", OME_Funcall, saCmsSetPORFreq, NULL, 0 },
|
||||
{ "CUR FREQ", OME_UINT16 | DYNAMIC, NULL, &(OSD_UINT16_t){ &saCmsORFreq, 5000, 5999, 0 } },
|
||||
{ "NEW FREQ", OME_UINT16, NULL, &(OSD_UINT16_t){ &saCmsORFreqNew, 5000, 5999, 1 } },
|
||||
{ "SET", OME_Funcall, saCmsSetPORFreq, NULL },
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL }
|
||||
};
|
||||
|
||||
static CMS_Menu saCmsMenuPORFreq =
|
||||
|
@ -629,14 +629,14 @@ static CMS_Menu saCmsMenuPORFreq =
|
|||
};
|
||||
|
||||
static const OSD_Entry saCmsMenuUserFreqEntries[] = {
|
||||
{ "- USER FREQ -", OME_Label, NULL, NULL, 0 },
|
||||
{ "- USER FREQ -", OME_Label, NULL, NULL },
|
||||
|
||||
{ "CUR FREQ", OME_UINT16, NULL, &(OSD_UINT16_t){ &saCmsUserFreq, 5000, 5999, 0 }, DYNAMIC },
|
||||
{ "NEW FREQ", OME_UINT16, NULL, &(OSD_UINT16_t){ &saCmsUserFreqNew, 5000, 5999, 1 }, 0 },
|
||||
{ "SET", OME_Funcall, saCmsConfigUserFreq, NULL, 0 },
|
||||
{ "CUR FREQ", OME_UINT16 | DYNAMIC, NULL, &(OSD_UINT16_t){ &saCmsUserFreq, 5000, 5999, 0 } },
|
||||
{ "NEW FREQ", OME_UINT16, NULL, &(OSD_UINT16_t){ &saCmsUserFreqNew, 5000, 5999, 1 } },
|
||||
{ "SET", OME_Funcall, saCmsConfigUserFreq, NULL },
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL }
|
||||
};
|
||||
|
||||
static CMS_Menu saCmsMenuUserFreq =
|
||||
|
@ -654,18 +654,18 @@ static CMS_Menu saCmsMenuUserFreq =
|
|||
static OSD_TAB_t saCmsEntFselMode = { &saCmsFselModeNew, 1, saCmsFselModeNames };
|
||||
|
||||
static const OSD_Entry saCmsMenuConfigEntries[] = {
|
||||
{ "- SA CONFIG -", OME_Label, NULL, NULL, 0 },
|
||||
{ "- SA CONFIG -", OME_Label, NULL, NULL },
|
||||
|
||||
{ "OP MODEL", OME_TAB, saCmsConfigOpmodelByGvar, &(OSD_TAB_t){ &saCmsOpmodel, 2, saCmsOpmodelNames }, DYNAMIC },
|
||||
{ "FSEL MODE", OME_TAB, saCmsConfigFreqModeByGvar, &saCmsEntFselMode, DYNAMIC },
|
||||
{ "PIT FMODE", OME_TAB, saCmsConfigPitFModeByGvar, &saCmsEntPitFMode, 0 },
|
||||
{ "POR FREQ", OME_Submenu, (CMSEntryFuncPtr)saCmsORFreqGetString, &saCmsMenuPORFreq, OPTSTRING },
|
||||
{ "OP MODEL", OME_TAB | DYNAMIC, saCmsConfigOpmodelByGvar, &(OSD_TAB_t){ &saCmsOpmodel, 2, saCmsOpmodelNames } },
|
||||
{ "FSEL MODE", OME_TAB | DYNAMIC, saCmsConfigFreqModeByGvar, &saCmsEntFselMode },
|
||||
{ "PIT FMODE", OME_TAB, saCmsConfigPitFModeByGvar, &saCmsEntPitFMode },
|
||||
{ "POR FREQ", OME_Submenu | OPTSTRING, (CMSEntryFuncPtr)saCmsORFreqGetString, &saCmsMenuPORFreq },
|
||||
#ifdef USE_EXTENDED_CMS_MENUS
|
||||
{ "STATX", OME_Submenu, cmsMenuChange, &saCmsMenuStats, 0 },
|
||||
{ "STATX", OME_Submenu, cmsMenuChange, &saCmsMenuStats },
|
||||
#endif /* USE_EXTENDED_CMS_MENUS */
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
static CMS_Menu saCmsMenuConfig = {
|
||||
|
@ -680,12 +680,12 @@ static CMS_Menu saCmsMenuConfig = {
|
|||
};
|
||||
|
||||
static const OSD_Entry saCmsMenuCommenceEntries[] = {
|
||||
{ "CONFIRM", OME_Label, NULL, NULL, 0 },
|
||||
{ "CONFIRM", OME_Label, NULL, NULL },
|
||||
|
||||
{ "YES", OME_Funcall, saCmsCommence, NULL, 0 },
|
||||
{ "YES", OME_Funcall, saCmsCommence, NULL },
|
||||
|
||||
{ "NO", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "NO", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL }
|
||||
};
|
||||
|
||||
static CMS_Menu saCmsMenuCommence = {
|
||||
|
@ -700,47 +700,47 @@ static CMS_Menu saCmsMenuCommence = {
|
|||
};
|
||||
|
||||
static const OSD_Entry saCmsMenuFreqModeEntries[] = {
|
||||
{ "- SMARTAUDIO -", OME_Label, NULL, NULL, 0 },
|
||||
{ "- SMARTAUDIO -", OME_Label, NULL, NULL },
|
||||
|
||||
{ "", OME_Label, NULL, saCmsStatusString, DYNAMIC },
|
||||
{ "FREQ", OME_Submenu, (CMSEntryFuncPtr)saCmsUserFreqGetString, &saCmsMenuUserFreq, OPTSTRING },
|
||||
{ "POWER", OME_TAB, saCmsConfigPowerByGvar, &saCmsEntPower, DYNAMIC },
|
||||
{ "PIT", OME_TAB, saCmsConfigPitByGvar, &saCmsEntPit, DYNAMIC },
|
||||
{ "SET", OME_Submenu, cmsMenuChange, &saCmsMenuCommence, 0 },
|
||||
{ "CONFIG", OME_Submenu, cmsMenuChange, &saCmsMenuConfig, 0 },
|
||||
{ "", OME_Label | DYNAMIC, NULL, saCmsStatusString },
|
||||
{ "FREQ", OME_Submenu | OPTSTRING, (CMSEntryFuncPtr)saCmsUserFreqGetString, &saCmsMenuUserFreq },
|
||||
{ "POWER", OME_TAB | DYNAMIC, saCmsConfigPowerByGvar, &saCmsEntPower },
|
||||
{ "PIT", OME_TAB | DYNAMIC, saCmsConfigPitByGvar, &saCmsEntPit },
|
||||
{ "SET", OME_Submenu, cmsMenuChange, &saCmsMenuCommence },
|
||||
{ "CONFIG", OME_Submenu, cmsMenuChange, &saCmsMenuConfig },
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
|
||||
static const OSD_Entry saCmsMenuChanModeEntries[] =
|
||||
{
|
||||
{ "- SMARTAUDIO -", OME_Label, NULL, NULL, 0 },
|
||||
{ "- SMARTAUDIO -", OME_Label, NULL, NULL },
|
||||
|
||||
{ "", OME_Label, NULL, saCmsStatusString, DYNAMIC },
|
||||
{ "BAND", OME_TAB, saCmsConfigBandByGvar, &saCmsEntBand, 0 },
|
||||
{ "CHAN", OME_TAB, saCmsConfigChanByGvar, &saCmsEntChan, 0 },
|
||||
{ "(FREQ)", OME_UINT16, NULL, &saCmsEntFreqRef, DYNAMIC },
|
||||
{ "POWER", OME_TAB, saCmsConfigPowerByGvar, &saCmsEntPower, DYNAMIC },
|
||||
{ "PIT", OME_TAB, saCmsConfigPitByGvar, &saCmsEntPit, DYNAMIC },
|
||||
{ "SET", OME_Submenu, cmsMenuChange, &saCmsMenuCommence, 0 },
|
||||
{ "CONFIG", OME_Submenu, cmsMenuChange, &saCmsMenuConfig, 0 },
|
||||
{ "", OME_Label | DYNAMIC, NULL, saCmsStatusString },
|
||||
{ "BAND", OME_TAB, saCmsConfigBandByGvar, &saCmsEntBand },
|
||||
{ "CHAN", OME_TAB, saCmsConfigChanByGvar, &saCmsEntChan },
|
||||
{ "(FREQ)", OME_UINT16 | DYNAMIC, NULL, &saCmsEntFreqRef },
|
||||
{ "POWER", OME_TAB | DYNAMIC, saCmsConfigPowerByGvar, &saCmsEntPower },
|
||||
{ "PIT", OME_TAB | DYNAMIC, saCmsConfigPitByGvar, &saCmsEntPit },
|
||||
{ "SET", OME_Submenu, cmsMenuChange, &saCmsMenuCommence },
|
||||
{ "CONFIG", OME_Submenu, cmsMenuChange, &saCmsMenuConfig },
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL }
|
||||
};
|
||||
|
||||
static const OSD_Entry saCmsMenuOfflineEntries[] =
|
||||
{
|
||||
{ "- VTX SMARTAUDIO -", OME_Label, NULL, NULL, 0 },
|
||||
{ "- VTX SMARTAUDIO -", OME_Label, NULL, NULL },
|
||||
|
||||
{ "", OME_Label, NULL, saCmsStatusString, DYNAMIC },
|
||||
{ "", OME_Label | DYNAMIC, NULL, saCmsStatusString },
|
||||
#ifdef USE_EXTENDED_CMS_MENUS
|
||||
{ "STATX", OME_Submenu, cmsMenuChange, &saCmsMenuStats, 0 },
|
||||
{ "STATX", OME_Submenu, cmsMenuChange, &saCmsMenuStats },
|
||||
#endif /* USE_EXTENDED_CMS_MENUS */
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL }
|
||||
};
|
||||
|
||||
CMS_Menu cmsx_menuVtxSmartAudio; // Forward
|
||||
|
|
|
@ -248,10 +248,10 @@ static const void *trampCmsOnEnter(displayPort_t *pDisp)
|
|||
}
|
||||
|
||||
static const OSD_Entry trampCmsMenuCommenceEntries[] = {
|
||||
{ "CONFIRM", OME_Label, NULL, NULL, 0 },
|
||||
{ "YES", OME_Funcall, trampCmsCommence, NULL, 0 },
|
||||
{ "NO", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "CONFIRM", OME_Label, NULL, NULL },
|
||||
{ "YES", OME_Funcall, trampCmsCommence, NULL },
|
||||
{ "NO", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL }
|
||||
};
|
||||
|
||||
static CMS_Menu trampCmsMenuCommence = {
|
||||
|
@ -267,19 +267,19 @@ static CMS_Menu trampCmsMenuCommence = {
|
|||
|
||||
static const OSD_Entry trampMenuEntries[] =
|
||||
{
|
||||
{ "- TRAMP -", OME_Label, NULL, NULL, 0 },
|
||||
{ "- TRAMP -", OME_Label, NULL, NULL },
|
||||
|
||||
{ "", OME_Label, NULL, trampCmsStatusString, DYNAMIC },
|
||||
{ "PIT", OME_TAB, trampCmsSetPitMode, &trampCmsEntPitMode, 0 },
|
||||
{ "BAND", OME_TAB, trampCmsConfigBand, &trampCmsEntBand, 0 },
|
||||
{ "CHAN", OME_TAB, trampCmsConfigChan, &trampCmsEntChan, 0 },
|
||||
{ "(FREQ)", OME_UINT16, NULL, &trampCmsEntFreqRef, DYNAMIC },
|
||||
{ "POWER", OME_TAB, trampCmsConfigPower, &trampCmsEntPower, 0 },
|
||||
{ "T(C)", OME_INT16, NULL, &trampCmsEntTemp, DYNAMIC },
|
||||
{ "SET", OME_Submenu, cmsMenuChange, &trampCmsMenuCommence, 0 },
|
||||
{ "", OME_Label | DYNAMIC, NULL, trampCmsStatusString },
|
||||
{ "PIT", OME_TAB, trampCmsSetPitMode, &trampCmsEntPitMode },
|
||||
{ "BAND", OME_TAB, trampCmsConfigBand, &trampCmsEntBand },
|
||||
{ "CHAN", OME_TAB, trampCmsConfigChan, &trampCmsEntChan },
|
||||
{ "(FREQ)", OME_UINT16 | DYNAMIC, NULL, &trampCmsEntFreqRef },
|
||||
{ "POWER", OME_TAB, trampCmsConfigPower, &trampCmsEntPower },
|
||||
{ "T(C)", OME_INT16 | DYNAMIC, NULL, &trampCmsEntTemp },
|
||||
{ "SET", OME_Submenu, cmsMenuChange, &trampCmsMenuCommence },
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL }
|
||||
};
|
||||
|
||||
CMS_Menu cmsx_menuVtxTramp = {
|
||||
|
|
|
@ -61,19 +61,24 @@ typedef const void *(*CMSEntryFuncPtr)(displayPort_t *displayPort, const void *p
|
|||
typedef struct
|
||||
{
|
||||
const char * text;
|
||||
OSD_MenuElement type;
|
||||
// Logical OR of OSD_MenuElement and flags below
|
||||
uint16_t flags;
|
||||
CMSEntryFuncPtr func;
|
||||
void *data;
|
||||
uint8_t flags;
|
||||
} __attribute__((packed)) OSD_Entry;
|
||||
|
||||
// Bits in flags
|
||||
#define PRINT_VALUE 0x01 // Value has been changed, need to redraw
|
||||
#define PRINT_LABEL 0x02 // Text label should be printed
|
||||
#define DYNAMIC 0x04 // Value should be updated dynamically
|
||||
#define OPTSTRING 0x08 // (Temporary) Flag for OME_Submenu, indicating func should be called to get a string to display.
|
||||
#define REBOOT_REQUIRED 0x10 // Reboot is required if the value is changed
|
||||
#define SCROLLING_TICKER 0x20// Long values are displayed as horizontally scrolling tickers (OME_TAB only)
|
||||
#define OSD_MENU_ELEMENT_MASK 0x001f
|
||||
#define PRINT_VALUE 0x0020 // Value has been changed, need to redraw
|
||||
#define PRINT_LABEL 0x0040 // Text label should be printed
|
||||
#define DYNAMIC 0x0080 // Value should be updated dynamically
|
||||
#define OPTSTRING 0x0100 // (Temporary) Flag for OME_Submenu, indicating func should be called to get a string to display.
|
||||
#define REBOOT_REQUIRED 0x0200 // Reboot is required if the value is changed
|
||||
#define SCROLLING_TICKER 0x0400 // Long values are displayed as horizontally scrolling tickers (OME_TAB only)
|
||||
#define SLIDER_RP 0x0800 // Value should be read only if simplified RP slider is enabled
|
||||
#define SLIDER_RPY 0x1000 // Value should be read only if simplified RPY slider is enabled
|
||||
#define SLIDER_GYRO 0x2000 // Value should be read only if simplified gyro slider is enabled
|
||||
#define SLIDER_DTERM 0x4000 // Value should be read only if simplified D term slider is enabled
|
||||
|
||||
#define IS_PRINTVALUE(x) ((x) & PRINT_VALUE)
|
||||
#define SET_PRINTVALUE(x) do { (x) |= PRINT_VALUE; } while (0)
|
||||
|
|
|
@ -125,10 +125,10 @@ TEST(CMSUnittest, TestCmsMenuKey)
|
|||
extern "C" {
|
||||
static const OSD_Entry menuMainEntries[] =
|
||||
{
|
||||
{"-- MAIN MENU --", OME_Label, NULL, NULL, 0},
|
||||
{"SAVE&REBOOT", OME_OSD_Exit, cmsMenuExit, (void*)1, 0},
|
||||
{"EXIT", OME_OSD_Exit, cmsMenuExit, (void*)0, 0},
|
||||
{NULL, OME_END, NULL, NULL, 0}
|
||||
{"-- MAIN MENU --", OME_Label, NULL, NULL},
|
||||
{"SAVE&REBOOT", OME_OSD_Exit, cmsMenuExit, (void*)1},
|
||||
{"EXIT", OME_OSD_Exit, cmsMenuExit, (void*)0},
|
||||
{NULL, OME_END, NULL, NULL}
|
||||
};
|
||||
CMS_Menu cmsx_menuMain = {
|
||||
#ifdef CMS_MENU_DEBUG
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue