Fixed 'cast-function-type' warnings, reworked CMS function poin… (#9236)
Fixed 'cast-function-type' warnings, reworked CMS function pointer juggle.
This commit is contained in:
commit
22fbb47a6a
3
Makefile
3
Makefile
|
@ -239,8 +239,7 @@ CC_NO_OPTIMISATION :=
|
||||||
#
|
#
|
||||||
# Added after GCC version update, remove once the warnings have been fixed
|
# Added after GCC version update, remove once the warnings have been fixed
|
||||||
#
|
#
|
||||||
TEMPORARY_FLAGS := -Wno-cast-function-type \
|
TEMPORARY_FLAGS := -Wno-address-of-packed-member \
|
||||||
-Wno-address-of-packed-member \
|
|
||||||
-Wno-absolute-value
|
-Wno-absolute-value
|
||||||
|
|
||||||
CFLAGS += $(ARCH_FLAGS) \
|
CFLAGS += $(ARCH_FLAGS) \
|
||||||
|
|
|
@ -94,6 +94,8 @@ static int cmsCurrentDevice = -1;
|
||||||
static unsigned int osdProfileCursor = 1;
|
static unsigned int osdProfileCursor = 1;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
int menuChainBack;
|
||||||
|
|
||||||
bool cmsDisplayPortRegister(displayPort_t *pDisplay)
|
bool cmsDisplayPortRegister(displayPort_t *pDisplay)
|
||||||
{
|
{
|
||||||
if (cmsDeviceCount == CMS_MAX_DEVICE)
|
if (cmsDeviceCount == CMS_MAX_DEVICE)
|
||||||
|
@ -400,7 +402,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t
|
||||||
|
|
||||||
// Special case of sub menu entry with optional value display.
|
// Special case of sub menu entry with optional value display.
|
||||||
|
|
||||||
char *str = ((CMSMenuOptFuncPtr)p->func)();
|
const char *str = p->func(pDisplay, p->data);
|
||||||
strncpy(buff, str, CMS_DRAW_BUFFER_LEN);
|
strncpy(buff, str, CMS_DRAW_BUFFER_LEN);
|
||||||
} else if (p->type == OME_Funcall && p->data) {
|
} else if (p->type == OME_Funcall && p->data) {
|
||||||
strncpy(buff, p->data, CMS_DRAW_BUFFER_LEN);
|
strncpy(buff, p->data, CMS_DRAW_BUFFER_LEN);
|
||||||
|
@ -537,7 +539,35 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t
|
||||||
return cnt;
|
return cnt;
|
||||||
}
|
}
|
||||||
|
|
||||||
STATIC_UNIT_TESTED long cmsMenuBack(displayPort_t *pDisplay); // Forward; will be resolved after merging
|
static void cmsMenuCountPage(displayPort_t *pDisplay)
|
||||||
|
{
|
||||||
|
UNUSED(pDisplay);
|
||||||
|
const OSD_Entry *p;
|
||||||
|
for (p = currentCtx.menu->entries; p->type != OME_END; p++);
|
||||||
|
pageCount = (p - currentCtx.menu->entries - 1) / maxMenuItems + 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
STATIC_UNIT_TESTED const void *cmsMenuBack(displayPort_t *pDisplay)
|
||||||
|
{
|
||||||
|
// Let onExit function decide whether to allow exit or not.
|
||||||
|
|
||||||
|
if (currentCtx.menu->onExit) {
|
||||||
|
return currentCtx.menu->onExit(pageTop + currentCtx.cursorRow);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!menuStackIdx) {
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
currentCtx = menuStack[--menuStackIdx];
|
||||||
|
|
||||||
|
cmsMenuCountPage(pDisplay);
|
||||||
|
cmsPageSelect(pDisplay, currentCtx.page);
|
||||||
|
|
||||||
|
cmsPageDebug();
|
||||||
|
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs)
|
static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs)
|
||||||
{
|
{
|
||||||
|
@ -600,7 +630,7 @@ static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs)
|
||||||
}
|
}
|
||||||
|
|
||||||
if (currentCtx.menu->onDisplayUpdate) {
|
if (currentCtx.menu->onDisplayUpdate) {
|
||||||
long result = currentCtx.menu->onDisplayUpdate(pageTop + currentCtx.cursorRow);
|
const void *result = currentCtx.menu->onDisplayUpdate(pageTop + currentCtx.cursorRow);
|
||||||
if (result == MENU_CHAIN_BACK) {
|
if (result == MENU_CHAIN_BACK) {
|
||||||
cmsMenuBack(pDisplay);
|
cmsMenuBack(pDisplay);
|
||||||
|
|
||||||
|
@ -634,20 +664,12 @@ static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static void cmsMenuCountPage(displayPort_t *pDisplay)
|
const void *cmsMenuChange(displayPort_t *pDisplay, const void *ptr)
|
||||||
{
|
|
||||||
UNUSED(pDisplay);
|
|
||||||
const OSD_Entry *p;
|
|
||||||
for (p = currentCtx.menu->entries; p->type != OME_END; p++);
|
|
||||||
pageCount = (p - currentCtx.menu->entries - 1) / maxMenuItems + 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
long cmsMenuChange(displayPort_t *pDisplay, const void *ptr)
|
|
||||||
{
|
{
|
||||||
const CMS_Menu *pMenu = (const CMS_Menu *)ptr;
|
const CMS_Menu *pMenu = (const CMS_Menu *)ptr;
|
||||||
|
|
||||||
if (!pMenu) {
|
if (!pMenu) {
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef CMS_MENU_DEBUG
|
#ifdef CMS_MENU_DEBUG
|
||||||
|
@ -666,7 +688,7 @@ long cmsMenuChange(displayPort_t *pDisplay, const void *ptr)
|
||||||
// Stack the current menu and move to a new menu.
|
// Stack the current menu and move to a new menu.
|
||||||
if (menuStackIdx >= CMS_MENU_STACK_LIMIT - 1) {
|
if (menuStackIdx >= CMS_MENU_STACK_LIMIT - 1) {
|
||||||
// menu stack limit reached - prevent array overflow
|
// menu stack limit reached - prevent array overflow
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
menuStack[menuStackIdx++] = currentCtx;
|
menuStack[menuStackIdx++] = currentCtx;
|
||||||
|
@ -675,7 +697,7 @@ long cmsMenuChange(displayPort_t *pDisplay, const void *ptr)
|
||||||
currentCtx.cursorRow = 0;
|
currentCtx.cursorRow = 0;
|
||||||
|
|
||||||
if (pMenu->onEnter) {
|
if (pMenu->onEnter) {
|
||||||
long result = pMenu->onEnter();
|
const void *result = pMenu->onEnter();
|
||||||
if (result == MENU_CHAIN_BACK) {
|
if (result == MENU_CHAIN_BACK) {
|
||||||
return cmsMenuBack(pDisplay);
|
return cmsMenuBack(pDisplay);
|
||||||
}
|
}
|
||||||
|
@ -695,32 +717,7 @@ long cmsMenuChange(displayPort_t *pDisplay, const void *ptr)
|
||||||
|
|
||||||
cmsPageDebug();
|
cmsPageDebug();
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
|
||||||
|
|
||||||
STATIC_UNIT_TESTED long cmsMenuBack(displayPort_t *pDisplay)
|
|
||||||
{
|
|
||||||
// Let onExit function decide whether to allow exit or not.
|
|
||||||
|
|
||||||
if (currentCtx.menu->onExit) {
|
|
||||||
long result = currentCtx.menu->onExit(pageTop + currentCtx.cursorRow);
|
|
||||||
if (result < 0) {
|
|
||||||
return MENU_CHAIN_BACK;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!menuStackIdx) {
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
currentCtx = menuStack[--menuStackIdx];
|
|
||||||
|
|
||||||
cmsMenuCountPage(pDisplay);
|
|
||||||
cmsPageSelect(pDisplay, currentCtx.page);
|
|
||||||
|
|
||||||
cmsPageDebug();
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void cmsMenuOpen(void)
|
void cmsMenuOpen(void)
|
||||||
|
@ -788,7 +785,7 @@ static void cmsTraverseGlobalExit(const CMS_Menu *pMenu)
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
long cmsMenuExit(displayPort_t *pDisplay, const void *ptr)
|
const void *cmsMenuExit(displayPort_t *pDisplay, const void *ptr)
|
||||||
{
|
{
|
||||||
int exitType = (int)ptr;
|
int exitType = (int)ptr;
|
||||||
switch (exitType) {
|
switch (exitType) {
|
||||||
|
@ -839,7 +836,7 @@ long cmsMenuExit(displayPort_t *pDisplay, const void *ptr)
|
||||||
|
|
||||||
unsetArmingDisabled(ARMING_DISABLED_CMS_MENU);
|
unsetArmingDisabled(ARMING_DISABLED_CMS_MENU);
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Stick/key detection and key codes
|
// Stick/key detection and key codes
|
||||||
|
@ -923,7 +920,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, cms_key_e key)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case OME_Funcall:;
|
case OME_Funcall:;
|
||||||
long retval;
|
const void *retval;
|
||||||
if (p->func && key == CMS_KEY_RIGHT) {
|
if (p->func && key == CMS_KEY_RIGHT) {
|
||||||
retval = p->func(pDisplay, p->data);
|
retval = p->func(pDisplay, p->data);
|
||||||
if (retval == MENU_CHAIN_BACK) {
|
if (retval == MENU_CHAIN_BACK) {
|
||||||
|
|
|
@ -48,8 +48,8 @@ void cmsHandler(timeUs_t currentTimeUs);
|
||||||
|
|
||||||
bool cmsDisplayPortSelect(displayPort_t *instance);
|
bool cmsDisplayPortSelect(displayPort_t *instance);
|
||||||
void cmsMenuOpen(void);
|
void cmsMenuOpen(void);
|
||||||
long cmsMenuChange(displayPort_t *pPort, const void *ptr);
|
const void *cmsMenuChange(displayPort_t *pPort, const void *ptr);
|
||||||
long cmsMenuExit(displayPort_t *pPort, const void *ptr);
|
const void *cmsMenuExit(displayPort_t *pPort, const void *ptr);
|
||||||
void cmsSetExternKey(cms_key_e extKey);
|
void cmsSetExternKey(cms_key_e extKey);
|
||||||
|
|
||||||
#define CMS_STARTUP_HELP_TEXT1 "MENU:THR MID"
|
#define CMS_STARTUP_HELP_TEXT1 "MENU:THR MID"
|
||||||
|
|
|
@ -148,12 +148,12 @@ static void cmsx_Blackbox_GetDeviceStatus(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_FLASHFS
|
#ifdef USE_FLASHFS
|
||||||
static long cmsx_EraseFlash(displayPort_t *pDisplay, const void *ptr)
|
static const void *cmsx_EraseFlash(displayPort_t *pDisplay, const void *ptr)
|
||||||
{
|
{
|
||||||
UNUSED(ptr);
|
UNUSED(ptr);
|
||||||
|
|
||||||
if (!flashfsIsSupported()) {
|
if (!flashfsIsSupported()) {
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
displayClearScreen(pDisplay);
|
displayClearScreen(pDisplay);
|
||||||
|
@ -172,20 +172,20 @@ static long cmsx_EraseFlash(displayPort_t *pDisplay, const void *ptr)
|
||||||
// Update storage device status to show new used space amount
|
// Update storage device status to show new used space amount
|
||||||
cmsx_Blackbox_GetDeviceStatus();
|
cmsx_Blackbox_GetDeviceStatus();
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
#endif // USE_FLASHFS
|
#endif // USE_FLASHFS
|
||||||
|
|
||||||
static long cmsx_Blackbox_onEnter(void)
|
static const void *cmsx_Blackbox_onEnter(void)
|
||||||
{
|
{
|
||||||
cmsx_Blackbox_GetDeviceStatus();
|
cmsx_Blackbox_GetDeviceStatus();
|
||||||
cmsx_BlackboxDevice = blackboxConfig()->device;
|
cmsx_BlackboxDevice = blackboxConfig()->device;
|
||||||
|
|
||||||
blackboxConfig_p_ratio = blackboxConfig()->p_ratio;
|
blackboxConfig_p_ratio = blackboxConfig()->p_ratio;
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_Blackbox_onExit(const OSD_Entry *self)
|
static const void *cmsx_Blackbox_onExit(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
|
@ -194,7 +194,8 @@ static long cmsx_Blackbox_onExit(const OSD_Entry *self)
|
||||||
blackboxValidateConfig();
|
blackboxValidateConfig();
|
||||||
}
|
}
|
||||||
blackboxConfigMutable()->p_ratio = blackboxConfig_p_ratio;
|
blackboxConfigMutable()->p_ratio = blackboxConfig_p_ratio;
|
||||||
return 0;
|
|
||||||
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static const OSD_Entry cmsx_menuBlackboxEntries[] =
|
static const OSD_Entry cmsx_menuBlackboxEntries[] =
|
||||||
|
|
|
@ -48,16 +48,17 @@ uint8_t failsafeConfig_failsafe_delay;
|
||||||
uint8_t failsafeConfig_failsafe_off_delay;
|
uint8_t failsafeConfig_failsafe_off_delay;
|
||||||
uint16_t failsafeConfig_failsafe_throttle;
|
uint16_t failsafeConfig_failsafe_throttle;
|
||||||
|
|
||||||
static long cmsx_Failsafe_onEnter(void)
|
static const void *cmsx_Failsafe_onEnter(void)
|
||||||
{
|
{
|
||||||
failsafeConfig_failsafe_procedure = failsafeConfig()->failsafe_procedure;
|
failsafeConfig_failsafe_procedure = failsafeConfig()->failsafe_procedure;
|
||||||
failsafeConfig_failsafe_delay = failsafeConfig()->failsafe_delay;
|
failsafeConfig_failsafe_delay = failsafeConfig()->failsafe_delay;
|
||||||
failsafeConfig_failsafe_off_delay = failsafeConfig()->failsafe_off_delay;
|
failsafeConfig_failsafe_off_delay = failsafeConfig()->failsafe_off_delay;
|
||||||
failsafeConfig_failsafe_throttle = failsafeConfig()->failsafe_throttle;
|
failsafeConfig_failsafe_throttle = failsafeConfig()->failsafe_throttle;
|
||||||
return 0;
|
|
||||||
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_Failsafe_onExit(const OSD_Entry *self)
|
static const void *cmsx_Failsafe_onExit(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
|
@ -66,7 +67,7 @@ static long cmsx_Failsafe_onExit(const OSD_Entry *self)
|
||||||
failsafeConfigMutable()->failsafe_off_delay = failsafeConfig_failsafe_off_delay;
|
failsafeConfigMutable()->failsafe_off_delay = failsafeConfig_failsafe_off_delay;
|
||||||
failsafeConfigMutable()->failsafe_throttle = failsafeConfig_failsafe_throttle;
|
failsafeConfigMutable()->failsafe_throttle = failsafeConfig_failsafe_throttle;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static const OSD_Entry cmsx_menuFailsafeEntries[] =
|
static const OSD_Entry cmsx_menuFailsafeEntries[] =
|
||||||
|
|
|
@ -65,7 +65,7 @@ static char accCalibrationStatus[CALIBRATION_STATUS_MAX_LENGTH];
|
||||||
static char baroCalibrationStatus[CALIBRATION_STATUS_MAX_LENGTH];
|
static char baroCalibrationStatus[CALIBRATION_STATUS_MAX_LENGTH];
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static long cmsx_CalibrationOnDisplayUpdate(const OSD_Entry *selected)
|
static const void *cmsx_CalibrationOnDisplayUpdate(const OSD_Entry *selected)
|
||||||
{
|
{
|
||||||
UNUSED(selected);
|
UNUSED(selected);
|
||||||
|
|
||||||
|
@ -77,10 +77,10 @@ static long cmsx_CalibrationOnDisplayUpdate(const OSD_Entry *selected)
|
||||||
tfp_sprintf(baroCalibrationStatus, sensors(SENSOR_BARO) ? baroIsCalibrationComplete() ? CALIBRATION_STATUS_OK : CALIBRATION_STATUS_WAIT: CALIBRATION_STATUS_OFF);
|
tfp_sprintf(baroCalibrationStatus, sensors(SENSOR_BARO) ? baroIsCalibrationComplete() ? CALIBRATION_STATUS_OK : CALIBRATION_STATUS_WAIT: CALIBRATION_STATUS_OFF);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsCalibrateGyro(displayPort_t *pDisp, const void *self)
|
static const void *cmsCalibrateGyro(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
@ -89,11 +89,11 @@ static long cmsCalibrateGyro(displayPort_t *pDisp, const void *self)
|
||||||
gyroStartCalibration(false);
|
gyroStartCalibration(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(USE_ACC)
|
#if defined(USE_ACC)
|
||||||
static long cmsCalibrateAcc(displayPort_t *pDisp, const void *self)
|
static const void *cmsCalibrateAcc(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
@ -102,12 +102,12 @@ static long cmsCalibrateAcc(displayPort_t *pDisp, const void *self)
|
||||||
accStartCalibration();
|
accStartCalibration();
|
||||||
}
|
}
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(USE_BARO)
|
#if defined(USE_BARO)
|
||||||
static long cmsCalibrateBaro(displayPort_t *pDisp, const void *self)
|
static const void *cmsCalibrateBaro(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
@ -116,7 +116,7 @@ static long cmsCalibrateBaro(displayPort_t *pDisp, const void *self)
|
||||||
baroStartCalibration();
|
baroStartCalibration();
|
||||||
}
|
}
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -149,7 +149,7 @@ static CMS_Menu cmsx_menuCalibration = {
|
||||||
static char infoGitRev[GIT_SHORT_REVISION_LENGTH + 1];
|
static char infoGitRev[GIT_SHORT_REVISION_LENGTH + 1];
|
||||||
static char infoTargetName[] = __TARGET__;
|
static char infoTargetName[] = __TARGET__;
|
||||||
|
|
||||||
static long cmsx_FirmwareInit(void)
|
static const void *cmsx_FirmwareInit(void)
|
||||||
{
|
{
|
||||||
unsigned i;
|
unsigned i;
|
||||||
for (i = 0 ; i < GIT_SHORT_REVISION_LENGTH ; i++) {
|
for (i = 0 ; i < GIT_SHORT_REVISION_LENGTH ; i++) {
|
||||||
|
@ -162,7 +162,7 @@ static long cmsx_FirmwareInit(void)
|
||||||
|
|
||||||
infoGitRev[i] = 0x0; // Terminate string
|
infoGitRev[i] = 0x0; // Terminate string
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static const OSD_Entry menuFirmwareEntries[] = {
|
static const OSD_Entry menuFirmwareEntries[] = {
|
||||||
|
|
|
@ -59,7 +59,7 @@ static uint8_t gpsRescueConfig_altitudeMode;
|
||||||
static uint16_t gpsRescueConfig_ascendRate;
|
static uint16_t gpsRescueConfig_ascendRate;
|
||||||
static uint16_t gpsRescueConfig_descendRate;
|
static uint16_t gpsRescueConfig_descendRate;
|
||||||
|
|
||||||
static long cms_menuGpsRescuePidOnEnter(void)
|
static const void *cms_menuGpsRescuePidOnEnter(void)
|
||||||
{
|
{
|
||||||
|
|
||||||
gpsRescueConfig_throttleP = gpsRescueConfig()->throttleP;
|
gpsRescueConfig_throttleP = gpsRescueConfig()->throttleP;
|
||||||
|
@ -72,10 +72,10 @@ static long cms_menuGpsRescuePidOnEnter(void)
|
||||||
gpsRescueConfig_velI = gpsRescueConfig()->velI;
|
gpsRescueConfig_velI = gpsRescueConfig()->velI;
|
||||||
gpsRescueConfig_velD = gpsRescueConfig()->velD;
|
gpsRescueConfig_velD = gpsRescueConfig()->velD;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cms_menuGpsRescuePidOnExit(const OSD_Entry *self)
|
static const void *cms_menuGpsRescuePidOnExit(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
|
@ -89,7 +89,7 @@ static long cms_menuGpsRescuePidOnExit(const OSD_Entry *self)
|
||||||
gpsRescueConfigMutable()->velI = gpsRescueConfig_velI;
|
gpsRescueConfigMutable()->velI = gpsRescueConfig_velI;
|
||||||
gpsRescueConfigMutable()->velD = gpsRescueConfig_velD;
|
gpsRescueConfigMutable()->velD = gpsRescueConfig_velD;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
const OSD_Entry cms_menuGpsRescuePidEntries[] =
|
const OSD_Entry cms_menuGpsRescuePidEntries[] =
|
||||||
|
@ -121,7 +121,7 @@ CMS_Menu cms_menuGpsRescuePid = {
|
||||||
.entries = cms_menuGpsRescuePidEntries,
|
.entries = cms_menuGpsRescuePidEntries,
|
||||||
};
|
};
|
||||||
|
|
||||||
static long cmsx_menuGpsRescueOnEnter(void)
|
static const void *cmsx_menuGpsRescueOnEnter(void)
|
||||||
{
|
{
|
||||||
|
|
||||||
gpsRescueConfig_angle = gpsRescueConfig()->angle;
|
gpsRescueConfig_angle = gpsRescueConfig()->angle;
|
||||||
|
@ -140,10 +140,10 @@ static long cmsx_menuGpsRescueOnEnter(void)
|
||||||
gpsRescueConfig_ascendRate = gpsRescueConfig()->ascendRate;
|
gpsRescueConfig_ascendRate = gpsRescueConfig()->ascendRate;
|
||||||
gpsRescueConfig_descendRate = gpsRescueConfig()->descendRate;
|
gpsRescueConfig_descendRate = gpsRescueConfig()->descendRate;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_menuGpsRescueOnExit(const OSD_Entry *self)
|
static const void *cmsx_menuGpsRescueOnExit(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
|
@ -164,7 +164,7 @@ static long cmsx_menuGpsRescueOnExit(const OSD_Entry *self)
|
||||||
gpsRescueConfigMutable()->ascendRate = gpsRescueConfig_ascendRate;
|
gpsRescueConfigMutable()->ascendRate = gpsRescueConfig_ascendRate;
|
||||||
gpsRescueConfigMutable()->descendRate = gpsRescueConfig_descendRate;
|
gpsRescueConfigMutable()->descendRate = gpsRescueConfig_descendRate;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
const OSD_Entry cmsx_menuGpsRescueEntries[] =
|
const OSD_Entry cmsx_menuGpsRescueEntries[] =
|
||||||
|
|
|
@ -112,7 +112,7 @@ static void setProfileIndexString(char *profileString, int profileIndex, char *p
|
||||||
profileString[charIndex] = '\0';
|
profileString[charIndex] = '\0';
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_menuImu_onEnter(void)
|
static const void *cmsx_menuImu_onEnter(void)
|
||||||
{
|
{
|
||||||
pidProfileIndex = getCurrentPidProfileIndex();
|
pidProfileIndex = getCurrentPidProfileIndex();
|
||||||
tmpPidProfileIndex = pidProfileIndex + 1;
|
tmpPidProfileIndex = pidProfileIndex + 1;
|
||||||
|
@ -120,20 +120,20 @@ static long cmsx_menuImu_onEnter(void)
|
||||||
rateProfileIndex = getCurrentControlRateProfileIndex();
|
rateProfileIndex = getCurrentControlRateProfileIndex();
|
||||||
tmpRateProfileIndex = rateProfileIndex + 1;
|
tmpRateProfileIndex = rateProfileIndex + 1;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_menuImu_onExit(const OSD_Entry *self)
|
static const void *cmsx_menuImu_onExit(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
changePidProfile(pidProfileIndex);
|
changePidProfile(pidProfileIndex);
|
||||||
changeControlRateProfile(rateProfileIndex);
|
changeControlRateProfile(rateProfileIndex);
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_profileIndexOnChange(displayPort_t *displayPort, const void *ptr)
|
static const void *cmsx_profileIndexOnChange(displayPort_t *displayPort, const void *ptr)
|
||||||
{
|
{
|
||||||
UNUSED(displayPort);
|
UNUSED(displayPort);
|
||||||
UNUSED(ptr);
|
UNUSED(ptr);
|
||||||
|
@ -141,10 +141,10 @@ static long cmsx_profileIndexOnChange(displayPort_t *displayPort, const void *pt
|
||||||
pidProfileIndex = tmpPidProfileIndex - 1;
|
pidProfileIndex = tmpPidProfileIndex - 1;
|
||||||
changePidProfile(pidProfileIndex);
|
changePidProfile(pidProfileIndex);
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_rateProfileIndexOnChange(displayPort_t *displayPort, const void *ptr)
|
static const void *cmsx_rateProfileIndexOnChange(displayPort_t *displayPort, const void *ptr)
|
||||||
{
|
{
|
||||||
UNUSED(displayPort);
|
UNUSED(displayPort);
|
||||||
UNUSED(ptr);
|
UNUSED(ptr);
|
||||||
|
@ -152,10 +152,10 @@ static long cmsx_rateProfileIndexOnChange(displayPort_t *displayPort, const void
|
||||||
rateProfileIndex = tmpRateProfileIndex - 1;
|
rateProfileIndex = tmpRateProfileIndex - 1;
|
||||||
changeControlRateProfile(rateProfileIndex);
|
changeControlRateProfile(rateProfileIndex);
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_PidRead(void)
|
static const void *cmsx_PidRead(void)
|
||||||
{
|
{
|
||||||
|
|
||||||
const pidProfile_t *pidProfile = pidProfiles(pidProfileIndex);
|
const pidProfile_t *pidProfile = pidProfiles(pidProfileIndex);
|
||||||
|
@ -166,18 +166,18 @@ static long cmsx_PidRead(void)
|
||||||
tempPidF[i] = pidProfile->pid[i].F;
|
tempPidF[i] = pidProfile->pid[i].F;
|
||||||
}
|
}
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_PidOnEnter(void)
|
static const void *cmsx_PidOnEnter(void)
|
||||||
{
|
{
|
||||||
setProfileIndexString(pidProfileIndexString, pidProfileIndex, currentPidProfile->profileName);
|
setProfileIndexString(pidProfileIndexString, pidProfileIndex, currentPidProfile->profileName);
|
||||||
cmsx_PidRead();
|
cmsx_PidRead();
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_PidWriteback(const OSD_Entry *self)
|
static const void *cmsx_PidWriteback(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
|
@ -190,7 +190,7 @@ static long cmsx_PidWriteback(const OSD_Entry *self)
|
||||||
}
|
}
|
||||||
pidInitConfig(currentPidProfile);
|
pidInitConfig(currentPidProfile);
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static const OSD_Entry cmsx_menuPidEntries[] =
|
static const OSD_Entry cmsx_menuPidEntries[] =
|
||||||
|
@ -231,28 +231,28 @@ static CMS_Menu cmsx_menuPid = {
|
||||||
// Rate & Expo
|
// Rate & Expo
|
||||||
//
|
//
|
||||||
|
|
||||||
static long cmsx_RateProfileRead(void)
|
static const void *cmsx_RateProfileRead(void)
|
||||||
{
|
{
|
||||||
memcpy(&rateProfile, controlRateProfiles(rateProfileIndex), sizeof(controlRateConfig_t));
|
memcpy(&rateProfile, controlRateProfiles(rateProfileIndex), sizeof(controlRateConfig_t));
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_RateProfileWriteback(const OSD_Entry *self)
|
static const void *cmsx_RateProfileWriteback(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
memcpy(controlRateProfilesMutable(rateProfileIndex), &rateProfile, sizeof(controlRateConfig_t));
|
memcpy(controlRateProfilesMutable(rateProfileIndex), &rateProfile, sizeof(controlRateConfig_t));
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_RateProfileOnEnter(void)
|
static const void *cmsx_RateProfileOnEnter(void)
|
||||||
{
|
{
|
||||||
setProfileIndexString(rateProfileIndexString, rateProfileIndex, controlRateProfilesMutable(rateProfileIndex)->profileName);
|
setProfileIndexString(rateProfileIndexString, rateProfileIndex, controlRateProfilesMutable(rateProfileIndex)->profileName);
|
||||||
cmsx_RateProfileRead();
|
cmsx_RateProfileRead();
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static const OSD_Entry cmsx_menuRateProfileEntries[] =
|
static const OSD_Entry cmsx_menuRateProfileEntries[] =
|
||||||
|
@ -301,7 +301,7 @@ static uint8_t cmsx_launchControlThrottlePercent;
|
||||||
static uint8_t cmsx_launchControlAngleLimit;
|
static uint8_t cmsx_launchControlAngleLimit;
|
||||||
static uint8_t cmsx_launchControlGain;
|
static uint8_t cmsx_launchControlGain;
|
||||||
|
|
||||||
static long cmsx_launchControlOnEnter(void)
|
static const void *cmsx_launchControlOnEnter(void)
|
||||||
{
|
{
|
||||||
const pidProfile_t *pidProfile = pidProfiles(pidProfileIndex);
|
const pidProfile_t *pidProfile = pidProfiles(pidProfileIndex);
|
||||||
|
|
||||||
|
@ -311,10 +311,10 @@ static long cmsx_launchControlOnEnter(void)
|
||||||
cmsx_launchControlAngleLimit = pidProfile->launchControlAngleLimit;
|
cmsx_launchControlAngleLimit = pidProfile->launchControlAngleLimit;
|
||||||
cmsx_launchControlGain = pidProfile->launchControlGain;
|
cmsx_launchControlGain = pidProfile->launchControlGain;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_launchControlOnExit(const OSD_Entry *self)
|
static const void *cmsx_launchControlOnExit(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
|
@ -326,7 +326,7 @@ static long cmsx_launchControlOnExit(const OSD_Entry *self)
|
||||||
pidProfile->launchControlAngleLimit = cmsx_launchControlAngleLimit;
|
pidProfile->launchControlAngleLimit = cmsx_launchControlAngleLimit;
|
||||||
pidProfile->launchControlGain = cmsx_launchControlGain;
|
pidProfile->launchControlGain = cmsx_launchControlGain;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static const OSD_Entry cmsx_menuLaunchControlEntries[] = {
|
static const OSD_Entry cmsx_menuLaunchControlEntries[] = {
|
||||||
|
@ -376,7 +376,7 @@ static uint8_t cmsx_iterm_relax_type;
|
||||||
static uint8_t cmsx_iterm_relax_cutoff;
|
static uint8_t cmsx_iterm_relax_cutoff;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static long cmsx_profileOtherOnEnter(void)
|
static const void *cmsx_profileOtherOnEnter(void)
|
||||||
{
|
{
|
||||||
setProfileIndexString(pidProfileIndexString, pidProfileIndex, currentPidProfile->profileName);
|
setProfileIndexString(pidProfileIndexString, pidProfileIndex, currentPidProfile->profileName);
|
||||||
|
|
||||||
|
@ -410,10 +410,10 @@ static long cmsx_profileOtherOnEnter(void)
|
||||||
cmsx_iterm_relax_cutoff = pidProfile->iterm_relax_cutoff;
|
cmsx_iterm_relax_cutoff = pidProfile->iterm_relax_cutoff;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_profileOtherOnExit(const OSD_Entry *self)
|
static const void *cmsx_profileOtherOnExit(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
|
@ -448,7 +448,7 @@ static long cmsx_profileOtherOnExit(const OSD_Entry *self)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
initEscEndpoints();
|
initEscEndpoints();
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static const OSD_Entry cmsx_menuProfileOtherEntries[] = {
|
static const OSD_Entry cmsx_menuProfileOtherEntries[] = {
|
||||||
|
@ -508,7 +508,7 @@ static uint16_t gyroConfig_gyro_soft_notch_hz_2;
|
||||||
static uint16_t gyroConfig_gyro_soft_notch_cutoff_2;
|
static uint16_t gyroConfig_gyro_soft_notch_cutoff_2;
|
||||||
static uint8_t gyroConfig_gyro_to_use;
|
static uint8_t gyroConfig_gyro_to_use;
|
||||||
|
|
||||||
static long cmsx_menuGyro_onEnter(void)
|
static const void *cmsx_menuGyro_onEnter(void)
|
||||||
{
|
{
|
||||||
gyroConfig_gyro_lowpass_hz = gyroConfig()->gyro_lowpass_hz;
|
gyroConfig_gyro_lowpass_hz = gyroConfig()->gyro_lowpass_hz;
|
||||||
gyroConfig_gyro_lowpass2_hz = gyroConfig()->gyro_lowpass2_hz;
|
gyroConfig_gyro_lowpass2_hz = gyroConfig()->gyro_lowpass2_hz;
|
||||||
|
@ -518,10 +518,10 @@ static long cmsx_menuGyro_onEnter(void)
|
||||||
gyroConfig_gyro_soft_notch_cutoff_2 = gyroConfig()->gyro_soft_notch_cutoff_2;
|
gyroConfig_gyro_soft_notch_cutoff_2 = gyroConfig()->gyro_soft_notch_cutoff_2;
|
||||||
gyroConfig_gyro_to_use = gyroConfig()->gyro_to_use;
|
gyroConfig_gyro_to_use = gyroConfig()->gyro_to_use;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_menuGyro_onExit(const OSD_Entry *self)
|
static const void *cmsx_menuGyro_onExit(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
|
@ -533,7 +533,7 @@ static long cmsx_menuGyro_onExit(const OSD_Entry *self)
|
||||||
gyroConfigMutable()->gyro_soft_notch_cutoff_2 = gyroConfig_gyro_soft_notch_cutoff_2;
|
gyroConfigMutable()->gyro_soft_notch_cutoff_2 = gyroConfig_gyro_soft_notch_cutoff_2;
|
||||||
gyroConfigMutable()->gyro_to_use = gyroConfig_gyro_to_use;
|
gyroConfigMutable()->gyro_to_use = gyroConfig_gyro_to_use;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static const OSD_Entry cmsx_menuFilterGlobalEntries[] =
|
static const OSD_Entry cmsx_menuFilterGlobalEntries[] =
|
||||||
|
@ -582,7 +582,7 @@ static uint16_t dynFiltDtermMin;
|
||||||
static uint16_t dynFiltDtermMax;
|
static uint16_t dynFiltDtermMax;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static long cmsx_menuDynFilt_onEnter(void)
|
static const void *cmsx_menuDynFilt_onEnter(void)
|
||||||
{
|
{
|
||||||
#ifdef USE_GYRO_DATA_ANALYSE
|
#ifdef USE_GYRO_DATA_ANALYSE
|
||||||
dynFiltNotchRange = gyroConfig()->dyn_notch_range;
|
dynFiltNotchRange = gyroConfig()->dyn_notch_range;
|
||||||
|
@ -598,10 +598,10 @@ static long cmsx_menuDynFilt_onEnter(void)
|
||||||
dynFiltDtermMax = pidProfile->dyn_lpf_dterm_max_hz;
|
dynFiltDtermMax = pidProfile->dyn_lpf_dterm_max_hz;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_menuDynFilt_onExit(const OSD_Entry *self)
|
static const void *cmsx_menuDynFilt_onExit(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
|
@ -619,7 +619,7 @@ static long cmsx_menuDynFilt_onExit(const OSD_Entry *self)
|
||||||
pidProfile->dyn_lpf_dterm_max_hz = dynFiltDtermMax;
|
pidProfile->dyn_lpf_dterm_max_hz = dynFiltDtermMax;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static const OSD_Entry cmsx_menuDynFiltEntries[] =
|
static const OSD_Entry cmsx_menuDynFiltEntries[] =
|
||||||
|
@ -663,7 +663,7 @@ static uint16_t cmsx_dterm_notch_hz;
|
||||||
static uint16_t cmsx_dterm_notch_cutoff;
|
static uint16_t cmsx_dterm_notch_cutoff;
|
||||||
static uint16_t cmsx_yaw_lowpass_hz;
|
static uint16_t cmsx_yaw_lowpass_hz;
|
||||||
|
|
||||||
static long cmsx_FilterPerProfileRead(void)
|
static const void *cmsx_FilterPerProfileRead(void)
|
||||||
{
|
{
|
||||||
const pidProfile_t *pidProfile = pidProfiles(pidProfileIndex);
|
const pidProfile_t *pidProfile = pidProfiles(pidProfileIndex);
|
||||||
|
|
||||||
|
@ -673,10 +673,10 @@ static long cmsx_FilterPerProfileRead(void)
|
||||||
cmsx_dterm_notch_cutoff = pidProfile->dterm_notch_cutoff;
|
cmsx_dterm_notch_cutoff = pidProfile->dterm_notch_cutoff;
|
||||||
cmsx_yaw_lowpass_hz = pidProfile->yaw_lowpass_hz;
|
cmsx_yaw_lowpass_hz = pidProfile->yaw_lowpass_hz;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_FilterPerProfileWriteback(const OSD_Entry *self)
|
static const void *cmsx_FilterPerProfileWriteback(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
|
@ -688,7 +688,7 @@ static long cmsx_FilterPerProfileWriteback(const OSD_Entry *self)
|
||||||
pidProfile->dterm_notch_cutoff = cmsx_dterm_notch_cutoff;
|
pidProfile->dterm_notch_cutoff = cmsx_dterm_notch_cutoff;
|
||||||
pidProfile->yaw_lowpass_hz = cmsx_yaw_lowpass_hz;
|
pidProfile->yaw_lowpass_hz = cmsx_yaw_lowpass_hz;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static const OSD_Entry cmsx_menuFilterPerProfileEntries[] =
|
static const OSD_Entry cmsx_menuFilterPerProfileEntries[] =
|
||||||
|
@ -731,15 +731,15 @@ static const char * const cmsx_ProfileNames[] = {
|
||||||
static OSD_TAB_t cmsx_PidProfileTable = { &cmsx_dstPidProfile, 3, cmsx_ProfileNames };
|
static OSD_TAB_t cmsx_PidProfileTable = { &cmsx_dstPidProfile, 3, cmsx_ProfileNames };
|
||||||
static OSD_TAB_t cmsx_ControlRateProfileTable = { &cmsx_dstControlRateProfile, 3, cmsx_ProfileNames };
|
static OSD_TAB_t cmsx_ControlRateProfileTable = { &cmsx_dstControlRateProfile, 3, cmsx_ProfileNames };
|
||||||
|
|
||||||
static long cmsx_menuCopyProfile_onEnter(void)
|
static const void *cmsx_menuCopyProfile_onEnter(void)
|
||||||
{
|
{
|
||||||
cmsx_dstPidProfile = 0;
|
cmsx_dstPidProfile = 0;
|
||||||
cmsx_dstControlRateProfile = 0;
|
cmsx_dstControlRateProfile = 0;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_CopyPidProfile(displayPort_t *pDisplay, const void *ptr)
|
static const void *cmsx_CopyPidProfile(displayPort_t *pDisplay, const void *ptr)
|
||||||
{
|
{
|
||||||
UNUSED(pDisplay);
|
UNUSED(pDisplay);
|
||||||
UNUSED(ptr);
|
UNUSED(ptr);
|
||||||
|
@ -748,10 +748,10 @@ static long cmsx_CopyPidProfile(displayPort_t *pDisplay, const void *ptr)
|
||||||
pidCopyProfile(cmsx_dstPidProfile - 1, getCurrentPidProfileIndex());
|
pidCopyProfile(cmsx_dstPidProfile - 1, getCurrentPidProfileIndex());
|
||||||
}
|
}
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_CopyControlRateProfile(displayPort_t *pDisplay, const void *ptr)
|
static const void *cmsx_CopyControlRateProfile(displayPort_t *pDisplay, const void *ptr)
|
||||||
{
|
{
|
||||||
UNUSED(pDisplay);
|
UNUSED(pDisplay);
|
||||||
UNUSED(ptr);
|
UNUSED(ptr);
|
||||||
|
@ -760,7 +760,7 @@ static long cmsx_CopyControlRateProfile(displayPort_t *pDisplay, const void *ptr
|
||||||
copyControlRateProfile(cmsx_dstControlRateProfile - 1, getCurrentControlRateProfileIndex());
|
copyControlRateProfile(cmsx_dstControlRateProfile - 1, getCurrentControlRateProfileIndex());
|
||||||
}
|
}
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static const OSD_Entry cmsx_menuCopyProfileEntries[] =
|
static const OSD_Entry cmsx_menuCopyProfileEntries[] =
|
||||||
|
|
|
@ -65,7 +65,7 @@ const char * const ledProfileNames[LED_PROFILE_COUNT] = {
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
static long cmsx_Ledstrip_OnEnter(void)
|
static const void *cmsx_Ledstrip_OnEnter(void)
|
||||||
{
|
{
|
||||||
cmsx_FeatureLedstrip = featureIsEnabled(FEATURE_LED_STRIP) ? 1 : 0;
|
cmsx_FeatureLedstrip = featureIsEnabled(FEATURE_LED_STRIP) ? 1 : 0;
|
||||||
cmsx_ledProfile = getLedProfile();
|
cmsx_ledProfile = getLedProfile();
|
||||||
|
@ -77,10 +77,10 @@ static long cmsx_Ledstrip_OnEnter(void)
|
||||||
cmsx_ledVisualBeeper = ledStripConfig()->ledstrip_visual_beeper;
|
cmsx_ledVisualBeeper = ledStripConfig()->ledstrip_visual_beeper;
|
||||||
cmsx_ledVisualBeeperColor = ledStripConfig()->ledstrip_visual_beeper_color;
|
cmsx_ledVisualBeeperColor = ledStripConfig()->ledstrip_visual_beeper_color;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_Ledstrip_OnExit(const OSD_Entry *self)
|
static const void *cmsx_Ledstrip_OnExit(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
|
@ -101,7 +101,7 @@ static long cmsx_Ledstrip_OnExit(const OSD_Entry *self)
|
||||||
ledStripConfigMutable()->ledstrip_visual_beeper = cmsx_ledVisualBeeper;
|
ledStripConfigMutable()->ledstrip_visual_beeper = cmsx_ledVisualBeeper;
|
||||||
ledStripConfigMutable()->ledstrip_visual_beeper_color = cmsx_ledVisualBeeperColor;
|
ledStripConfigMutable()->ledstrip_visual_beeper_color = cmsx_ledVisualBeeperColor;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static const OSD_Entry cmsx_menuLedstripEntries[] =
|
static const OSD_Entry cmsx_menuLedstripEntries[] =
|
||||||
|
|
|
@ -88,7 +88,7 @@ static CMS_Menu cmsx_menuFeatures = {
|
||||||
.entries = menuFeaturesEntries,
|
.entries = menuFeaturesEntries,
|
||||||
};
|
};
|
||||||
|
|
||||||
static long cmsx_SaveExitMenu(displayPort_t *pDisplay, const void *ptr)
|
static const void *cmsx_SaveExitMenu(displayPort_t *pDisplay, const void *ptr)
|
||||||
{
|
{
|
||||||
UNUSED(ptr);
|
UNUSED(ptr);
|
||||||
|
|
||||||
|
@ -97,7 +97,7 @@ static long cmsx_SaveExitMenu(displayPort_t *pDisplay, const void *ptr)
|
||||||
} else {
|
} else {
|
||||||
cmsMenuChange(pDisplay, &cmsx_menuSaveExit);
|
cmsMenuChange(pDisplay, &cmsx_menuSaveExit);
|
||||||
}
|
}
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Main
|
// Main
|
||||||
|
|
|
@ -60,12 +60,12 @@
|
||||||
// Misc
|
// Misc
|
||||||
//
|
//
|
||||||
|
|
||||||
static long cmsx_menuRcConfirmBack(const OSD_Entry *self)
|
static const void *cmsx_menuRcConfirmBack(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
if (self && self->type == OME_Back)
|
if (self && self->type == OME_Back)
|
||||||
return 0;
|
return NULL;
|
||||||
else
|
else
|
||||||
return -1;
|
return MENU_CHAIN_BACK;
|
||||||
}
|
}
|
||||||
|
|
||||||
//
|
//
|
||||||
|
@ -105,17 +105,17 @@ static uint8_t motorConfig_digitalIdleOffsetValue;
|
||||||
static uint8_t rxConfig_fpvCamAngleDegrees;
|
static uint8_t rxConfig_fpvCamAngleDegrees;
|
||||||
static debugType_e systemConfig_debug_mode;
|
static debugType_e systemConfig_debug_mode;
|
||||||
|
|
||||||
static long cmsx_menuMiscOnEnter(void)
|
static const void *cmsx_menuMiscOnEnter(void)
|
||||||
{
|
{
|
||||||
motorConfig_minthrottle = motorConfig()->minthrottle;
|
motorConfig_minthrottle = motorConfig()->minthrottle;
|
||||||
motorConfig_digitalIdleOffsetValue = motorConfig()->digitalIdleOffsetValue / 10;
|
motorConfig_digitalIdleOffsetValue = motorConfig()->digitalIdleOffsetValue / 10;
|
||||||
rxConfig_fpvCamAngleDegrees = rxConfig()->fpvCamAngleDegrees;
|
rxConfig_fpvCamAngleDegrees = rxConfig()->fpvCamAngleDegrees;
|
||||||
systemConfig_debug_mode = systemConfig()->debug_mode;
|
systemConfig_debug_mode = systemConfig()->debug_mode;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_menuMiscOnExit(const OSD_Entry *self)
|
static const void *cmsx_menuMiscOnExit(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
|
@ -124,7 +124,7 @@ static long cmsx_menuMiscOnExit(const OSD_Entry *self)
|
||||||
rxConfigMutable()->fpvCamAngleDegrees = rxConfig_fpvCamAngleDegrees;
|
rxConfigMutable()->fpvCamAngleDegrees = rxConfig_fpvCamAngleDegrees;
|
||||||
systemConfigMutable()->debug_mode = systemConfig_debug_mode;
|
systemConfigMutable()->debug_mode = systemConfig_debug_mode;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static const OSD_Entry menuMiscEntries[]=
|
static const OSD_Entry menuMiscEntries[]=
|
||||||
|
|
|
@ -48,19 +48,19 @@
|
||||||
#ifdef USE_EXTENDED_CMS_MENUS
|
#ifdef USE_EXTENDED_CMS_MENUS
|
||||||
static uint16_t osdConfig_item_pos[OSD_ITEM_COUNT];
|
static uint16_t osdConfig_item_pos[OSD_ITEM_COUNT];
|
||||||
|
|
||||||
static long menuOsdActiveElemsOnEnter(void)
|
static const void *menuOsdActiveElemsOnEnter(void)
|
||||||
{
|
{
|
||||||
memcpy(&osdConfig_item_pos[0], &osdConfig()->item_pos[0], sizeof(uint16_t) * OSD_ITEM_COUNT);
|
memcpy(&osdConfig_item_pos[0], &osdConfig()->item_pos[0], sizeof(uint16_t) * OSD_ITEM_COUNT);
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long menuOsdActiveElemsOnExit(const OSD_Entry *self)
|
static const void *menuOsdActiveElemsOnExit(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
memcpy(&osdConfigMutable()->item_pos[0], &osdConfig_item_pos[0], sizeof(uint16_t) * OSD_ITEM_COUNT);
|
memcpy(&osdConfigMutable()->item_pos[0], &osdConfig_item_pos[0], sizeof(uint16_t) * OSD_ITEM_COUNT);
|
||||||
osdAnalyzeActiveElements();
|
osdAnalyzeActiveElements();
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
const OSD_Entry menuOsdActiveElemsEntries[] =
|
const OSD_Entry menuOsdActiveElemsEntries[] =
|
||||||
|
@ -171,7 +171,7 @@ static uint16_t osdConfig_distance_alarm;
|
||||||
static uint8_t batteryConfig_vbatDurationForWarning;
|
static uint8_t batteryConfig_vbatDurationForWarning;
|
||||||
static uint8_t batteryConfig_vbatDurationForCritical;
|
static uint8_t batteryConfig_vbatDurationForCritical;
|
||||||
|
|
||||||
static long menuAlarmsOnEnter(void)
|
static const void *menuAlarmsOnEnter(void)
|
||||||
{
|
{
|
||||||
osdConfig_rssi_alarm = osdConfig()->rssi_alarm;
|
osdConfig_rssi_alarm = osdConfig()->rssi_alarm;
|
||||||
osdConfig_link_quality_alarm = osdConfig()->link_quality_alarm;
|
osdConfig_link_quality_alarm = osdConfig()->link_quality_alarm;
|
||||||
|
@ -182,10 +182,10 @@ static long menuAlarmsOnEnter(void)
|
||||||
batteryConfig_vbatDurationForWarning = batteryConfig()->vbatDurationForWarning;
|
batteryConfig_vbatDurationForWarning = batteryConfig()->vbatDurationForWarning;
|
||||||
batteryConfig_vbatDurationForCritical = batteryConfig()->vbatDurationForCritical;
|
batteryConfig_vbatDurationForCritical = batteryConfig()->vbatDurationForCritical;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long menuAlarmsOnExit(const OSD_Entry *self)
|
static const void *menuAlarmsOnExit(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
|
@ -198,7 +198,7 @@ static long menuAlarmsOnExit(const OSD_Entry *self)
|
||||||
batteryConfigMutable()->vbatDurationForWarning = batteryConfig_vbatDurationForWarning;
|
batteryConfigMutable()->vbatDurationForWarning = batteryConfig_vbatDurationForWarning;
|
||||||
batteryConfigMutable()->vbatDurationForCritical = batteryConfig_vbatDurationForCritical;
|
batteryConfigMutable()->vbatDurationForCritical = batteryConfig_vbatDurationForCritical;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
const OSD_Entry menuAlarmsEntries[] =
|
const OSD_Entry menuAlarmsEntries[] =
|
||||||
|
@ -231,7 +231,7 @@ osd_timer_source_e timerSource[OSD_TIMER_COUNT];
|
||||||
osd_timer_precision_e timerPrecision[OSD_TIMER_COUNT];
|
osd_timer_precision_e timerPrecision[OSD_TIMER_COUNT];
|
||||||
uint8_t timerAlarm[OSD_TIMER_COUNT];
|
uint8_t timerAlarm[OSD_TIMER_COUNT];
|
||||||
|
|
||||||
static long menuTimersOnEnter(void)
|
static const void *menuTimersOnEnter(void)
|
||||||
{
|
{
|
||||||
for (int i = 0; i < OSD_TIMER_COUNT; i++) {
|
for (int i = 0; i < OSD_TIMER_COUNT; i++) {
|
||||||
const uint16_t timer = osdConfig()->timers[i];
|
const uint16_t timer = osdConfig()->timers[i];
|
||||||
|
@ -240,10 +240,10 @@ static long menuTimersOnEnter(void)
|
||||||
timerAlarm[i] = OSD_TIMER_ALARM(timer);
|
timerAlarm[i] = OSD_TIMER_ALARM(timer);
|
||||||
}
|
}
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long menuTimersOnExit(const OSD_Entry *self)
|
static const void *menuTimersOnExit(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
|
@ -251,7 +251,7 @@ static long menuTimersOnExit(const OSD_Entry *self)
|
||||||
osdConfigMutable()->timers[i] = OSD_TIMER(timerSource[i], timerPrecision[i], timerAlarm[i]);
|
osdConfigMutable()->timers[i] = OSD_TIMER(timerSource[i], timerPrecision[i], timerAlarm[i]);
|
||||||
}
|
}
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static const char * osdTimerPrecisionNames[] = {"SCND", "HDTH"};
|
static const char * osdTimerPrecisionNames[] = {"SCND", "HDTH"};
|
||||||
|
@ -291,7 +291,7 @@ static uint8_t displayPortProfileMax7456_whiteBrightness;
|
||||||
static uint8_t osdConfig_osdProfileIndex;
|
static uint8_t osdConfig_osdProfileIndex;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static long cmsx_menuOsdOnEnter(void)
|
static const void *cmsx_menuOsdOnEnter(void)
|
||||||
{
|
{
|
||||||
#ifdef USE_OSD_PROFILES
|
#ifdef USE_OSD_PROFILES
|
||||||
osdConfig_osdProfileIndex = osdConfig()->osdProfileIndex;
|
osdConfig_osdProfileIndex = osdConfig()->osdProfileIndex;
|
||||||
|
@ -303,10 +303,10 @@ static long cmsx_menuOsdOnEnter(void)
|
||||||
displayPortProfileMax7456_whiteBrightness = displayPortProfileMax7456()->whiteBrightness;
|
displayPortProfileMax7456_whiteBrightness = displayPortProfileMax7456()->whiteBrightness;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_menuOsdOnExit(const OSD_Entry *self)
|
static const void *cmsx_menuOsdOnExit(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
|
@ -320,7 +320,7 @@ static long cmsx_menuOsdOnExit(const OSD_Entry *self)
|
||||||
displayPortProfileMax7456Mutable()->whiteBrightness = displayPortProfileMax7456_whiteBrightness;
|
displayPortProfileMax7456Mutable()->whiteBrightness = displayPortProfileMax7456_whiteBrightness;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
const OSD_Entry cmsx_menuOsdEntries[] =
|
const OSD_Entry cmsx_menuOsdEntries[] =
|
||||||
|
|
|
@ -54,7 +54,7 @@ int16_t currentSensorVirtualConfig_scale;
|
||||||
int16_t currentSensorVirtualConfig_offset;
|
int16_t currentSensorVirtualConfig_offset;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static long cmsx_Power_onEnter(void)
|
static const void *cmsx_Power_onEnter(void)
|
||||||
{
|
{
|
||||||
batteryConfig_voltageMeterSource = batteryConfig()->voltageMeterSource;
|
batteryConfig_voltageMeterSource = batteryConfig()->voltageMeterSource;
|
||||||
batteryConfig_currentMeterSource = batteryConfig()->currentMeterSource;
|
batteryConfig_currentMeterSource = batteryConfig()->currentMeterSource;
|
||||||
|
@ -71,10 +71,10 @@ static long cmsx_Power_onEnter(void)
|
||||||
currentSensorVirtualConfig_offset = currentSensorVirtualConfig()->offset;
|
currentSensorVirtualConfig_offset = currentSensorVirtualConfig()->offset;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_Power_onExit(const OSD_Entry *self)
|
static const void *cmsx_Power_onExit(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
|
@ -93,7 +93,7 @@ static long cmsx_Power_onExit(const OSD_Entry *self)
|
||||||
currentSensorVirtualConfigMutable()->offset = currentSensorVirtualConfig_offset;
|
currentSensorVirtualConfigMutable()->offset = currentSensorVirtualConfig_offset;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static const OSD_Entry cmsx_menuPowerEntries[] =
|
static const OSD_Entry cmsx_menuPowerEntries[] =
|
||||||
|
|
|
@ -43,7 +43,7 @@
|
||||||
static char statusLine1[MAX_STATUS_LINE_LENGTH] = "";
|
static char statusLine1[MAX_STATUS_LINE_LENGTH] = "";
|
||||||
static char statusLine2[MAX_STATUS_LINE_LENGTH] = "";
|
static char statusLine2[MAX_STATUS_LINE_LENGTH] = "";
|
||||||
|
|
||||||
static long setStatusMessage(void)
|
static const void *setStatusMessage(void)
|
||||||
{
|
{
|
||||||
vtxDevice_t *device = vtxCommonDevice();
|
vtxDevice_t *device = vtxCommonDevice();
|
||||||
|
|
||||||
|
@ -61,7 +61,7 @@ static long setStatusMessage(void)
|
||||||
tfp_sprintf(&statusLine1[0], "UNKNOWN VTX TYPE");
|
tfp_sprintf(&statusLine1[0], "UNKNOWN VTX TYPE");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static const OSD_Entry vtxErrorMenuEntries[] =
|
static const OSD_Entry vtxErrorMenuEntries[] =
|
||||||
|
@ -87,7 +87,7 @@ static CMS_Menu cmsx_menuVtxError = {
|
||||||
// Redirect to the proper menu based on the vtx device type
|
// Redirect to the proper menu based on the vtx device type
|
||||||
// If device isn't valid or not a supported type then don't
|
// If device isn't valid or not a supported type then don't
|
||||||
// redirect and instead display a local informational menu.
|
// redirect and instead display a local informational menu.
|
||||||
long cmsSelectVtx(displayPort_t *pDisplay, const void *ptr)
|
const void *cmsSelectVtx(displayPort_t *pDisplay, const void *ptr)
|
||||||
{
|
{
|
||||||
UNUSED(ptr);
|
UNUSED(ptr);
|
||||||
|
|
||||||
|
@ -126,6 +126,6 @@ long cmsSelectVtx(displayPort_t *pDisplay, const void *ptr)
|
||||||
cmsMenuChange(pDisplay, &cmsx_menuVtxError);
|
cmsMenuChange(pDisplay, &cmsx_menuVtxError);
|
||||||
}
|
}
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -23,4 +23,4 @@
|
||||||
#include "cms/cms.h"
|
#include "cms/cms.h"
|
||||||
#include "cms/cms_types.h"
|
#include "cms/cms_types.h"
|
||||||
|
|
||||||
long cmsSelectVtx(displayPort_t *pDisplay, const void *ptr);
|
const void *cmsSelectVtx(displayPort_t *pDisplay, const void *ptr);
|
||||||
|
|
|
@ -78,7 +78,7 @@ static void cmsx_Vtx_ConfigWriteback(void)
|
||||||
saveConfigAndNotify();
|
saveConfigAndNotify();
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_Vtx_onEnter(void)
|
static const void *cmsx_Vtx_onEnter(void)
|
||||||
{
|
{
|
||||||
cmsx_Vtx_ConfigRead();
|
cmsx_Vtx_ConfigRead();
|
||||||
|
|
||||||
|
@ -94,57 +94,57 @@ static long cmsx_Vtx_onEnter(void)
|
||||||
entryVtxPower.max = vtxTablePowerLevels;
|
entryVtxPower.max = vtxTablePowerLevels;
|
||||||
entryVtxPower.names = vtxTablePowerLabels;
|
entryVtxPower.names = vtxTablePowerLabels;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_Vtx_onExit(const OSD_Entry *self)
|
static const void *cmsx_Vtx_onExit(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
vtxCommonSetPitMode(vtxCommonDevice(), cmsx_vtxPit);
|
vtxCommonSetPitMode(vtxCommonDevice(), cmsx_vtxPit);
|
||||||
cmsx_Vtx_ConfigWriteback();
|
cmsx_Vtx_ConfigWriteback();
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_Vtx_onBandChange(displayPort_t *pDisp, const void *self)
|
static const void *cmsx_Vtx_onBandChange(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
if (cmsx_vtxBand == 0) {
|
if (cmsx_vtxBand == 0) {
|
||||||
cmsx_vtxBand = 1;
|
cmsx_vtxBand = 1;
|
||||||
}
|
}
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_Vtx_onChanChange(displayPort_t *pDisp, const void *self)
|
static const void *cmsx_Vtx_onChanChange(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
if (cmsx_vtxChannel == 0) {
|
if (cmsx_vtxChannel == 0) {
|
||||||
cmsx_vtxChannel = 1;
|
cmsx_vtxChannel = 1;
|
||||||
}
|
}
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_Vtx_onPowerChange(displayPort_t *pDisp, const void *self)
|
static const void *cmsx_Vtx_onPowerChange(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
if (cmsx_vtxPower == 0) {
|
if (cmsx_vtxPower == 0) {
|
||||||
cmsx_vtxPower = 1;
|
cmsx_vtxPower = 1;
|
||||||
}
|
}
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long cmsx_Vtx_onPitChange(displayPort_t *pDisp, const void *self)
|
static const void *cmsx_Vtx_onPitChange(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
if (cmsx_vtxPit == 0) {
|
if (cmsx_vtxPit == 0) {
|
||||||
cmsx_vtxPit = 1;
|
cmsx_vtxPit = 1;
|
||||||
}
|
}
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static const OSD_Entry cmsx_menuVtxEntries[] = {
|
static const OSD_Entry cmsx_menuVtxEntries[] = {
|
||||||
|
|
|
@ -121,12 +121,12 @@ char saCmsStatusString[31] = "- -- ---- ---";
|
||||||
// m bc ffff ppp
|
// m bc ffff ppp
|
||||||
// 0123456789012
|
// 0123456789012
|
||||||
|
|
||||||
static long saCmsConfigOpmodelByGvar(displayPort_t *, const void *self);
|
static const void *saCmsConfigOpmodelByGvar(displayPort_t *, const void *self);
|
||||||
static long saCmsConfigPitFModeByGvar(displayPort_t *, const void *self);
|
static const void *saCmsConfigPitFModeByGvar(displayPort_t *, const void *self);
|
||||||
static long saCmsConfigBandByGvar(displayPort_t *, const void *self);
|
static const void *saCmsConfigBandByGvar(displayPort_t *, const void *self);
|
||||||
static long saCmsConfigChanByGvar(displayPort_t *, const void *self);
|
static const void *saCmsConfigChanByGvar(displayPort_t *, const void *self);
|
||||||
static long saCmsConfigPowerByGvar(displayPort_t *, const void *self);
|
static const void *saCmsConfigPowerByGvar(displayPort_t *, const void *self);
|
||||||
static long saCmsConfigPitByGvar(displayPort_t *, const void *self);
|
static const void *saCmsConfigPitByGvar(displayPort_t *, const void *self);
|
||||||
|
|
||||||
void saUpdateStatusString(void)
|
void saUpdateStatusString(void)
|
||||||
{
|
{
|
||||||
|
@ -204,7 +204,7 @@ void saCmsResetOpmodel()
|
||||||
saCmsOpmodel = SACMS_OPMODEL_UNDEF;
|
saCmsOpmodel = SACMS_OPMODEL_UNDEF;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long saCmsConfigBandByGvar(displayPort_t *pDisp, const void *self)
|
static const void *saCmsConfigBandByGvar(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
@ -212,13 +212,13 @@ static long saCmsConfigBandByGvar(displayPort_t *pDisp, const void *self)
|
||||||
if (saDevice.version == 0) {
|
if (saDevice.version == 0) {
|
||||||
// Bounce back; not online yet
|
// Bounce back; not online yet
|
||||||
saCmsBand = 0;
|
saCmsBand = 0;
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (saCmsBand == 0) {
|
if (saCmsBand == 0) {
|
||||||
// Bouce back, no going back to undef state
|
// Bouce back, no going back to undef state
|
||||||
saCmsBand = 1;
|
saCmsBand = 1;
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred) {
|
if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred) {
|
||||||
|
@ -227,10 +227,10 @@ static long saCmsConfigBandByGvar(displayPort_t *pDisp, const void *self)
|
||||||
|
|
||||||
saCmsFreqRef = vtxCommonLookupFrequency(vtxCommonDevice(), saCmsBand, saCmsChan);
|
saCmsFreqRef = vtxCommonLookupFrequency(vtxCommonDevice(), saCmsBand, saCmsChan);
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long saCmsConfigChanByGvar(displayPort_t *pDisp, const void *self)
|
static const void *saCmsConfigChanByGvar(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
@ -238,13 +238,13 @@ static long saCmsConfigChanByGvar(displayPort_t *pDisp, const void *self)
|
||||||
if (saDevice.version == 0) {
|
if (saDevice.version == 0) {
|
||||||
// Bounce back; not online yet
|
// Bounce back; not online yet
|
||||||
saCmsChan = 0;
|
saCmsChan = 0;
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (saCmsChan == 0) {
|
if (saCmsChan == 0) {
|
||||||
// Bounce back; no going back to undef state
|
// Bounce back; no going back to undef state
|
||||||
saCmsChan = 1;
|
saCmsChan = 1;
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred) {
|
if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred) {
|
||||||
|
@ -253,10 +253,10 @@ static long saCmsConfigChanByGvar(displayPort_t *pDisp, const void *self)
|
||||||
|
|
||||||
saCmsFreqRef = vtxCommonLookupFrequency(vtxCommonDevice(), saCmsBand, saCmsChan);
|
saCmsFreqRef = vtxCommonLookupFrequency(vtxCommonDevice(), saCmsBand, saCmsChan);
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long saCmsConfigPitByGvar(displayPort_t *pDisp, const void *self)
|
static const void *saCmsConfigPitByGvar(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
@ -266,21 +266,21 @@ static long saCmsConfigPitByGvar(displayPort_t *pDisp, const void *self)
|
||||||
if (saDevice.version == 0) {
|
if (saDevice.version == 0) {
|
||||||
// Bounce back; not online yet
|
// Bounce back; not online yet
|
||||||
saCmsPit = 0;
|
saCmsPit = 0;
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (saCmsPit == 0) {//trying to go back to undef state; bounce back
|
if (saCmsPit == 0) {//trying to go back to undef state; bounce back
|
||||||
saCmsPit = 1;
|
saCmsPit = 1;
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
if (saDevice.power != saCmsPower) {//we can't change both power and pit mode at once
|
if (saDevice.power != saCmsPower) {//we can't change both power and pit mode at once
|
||||||
saCmsPower = saDevice.power;
|
saCmsPower = saDevice.power;
|
||||||
}
|
}
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long saCmsConfigPowerByGvar(displayPort_t *pDisp, const void *self)
|
static const void *saCmsConfigPowerByGvar(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
@ -288,13 +288,13 @@ static long saCmsConfigPowerByGvar(displayPort_t *pDisp, const void *self)
|
||||||
if (saDevice.version == 0) {
|
if (saDevice.version == 0) {
|
||||||
// Bounce back; not online yet
|
// Bounce back; not online yet
|
||||||
saCmsPower = 0;
|
saCmsPower = 0;
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (saCmsPower == 0) {
|
if (saCmsPower == 0) {
|
||||||
// Bouce back; no going back to undef state
|
// Bouce back; no going back to undef state
|
||||||
saCmsPower = 1;
|
saCmsPower = 1;
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (saCmsPit > 0 && saCmsPit != 1 ) {
|
if (saCmsPit > 0 && saCmsPit != 1 ) {
|
||||||
|
@ -306,10 +306,10 @@ static long saCmsConfigPowerByGvar(displayPort_t *pDisp, const void *self)
|
||||||
}
|
}
|
||||||
dprintf(("saCmsConfigPowerByGvar: power index is now %d\r\n", saCmsPower));
|
dprintf(("saCmsConfigPowerByGvar: power index is now %d\r\n", saCmsPower));
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long saCmsConfigPitFModeByGvar(displayPort_t *pDisp, const void *self)
|
static const void *saCmsConfigPitFModeByGvar(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
@ -317,13 +317,13 @@ static long saCmsConfigPitFModeByGvar(displayPort_t *pDisp, const void *self)
|
||||||
if (saDevice.version == 1) {
|
if (saDevice.version == 1) {
|
||||||
// V1 device doesn't support PIT mode; bounce back.
|
// V1 device doesn't support PIT mode; bounce back.
|
||||||
saCmsPitFMode = 0;
|
saCmsPitFMode = 0;
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
if (saDevice.version >= 3) {
|
if (saDevice.version >= 3) {
|
||||||
// V2.1 device only supports PIR mode. and setting any flag immediately enables pit mode.
|
// V2.1 device only supports PIR mode. and setting any flag immediately enables pit mode.
|
||||||
//therefore: bounce back.
|
//therefore: bounce back.
|
||||||
saCmsPitFMode = 1;
|
saCmsPitFMode = 1;
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
dprintf(("saCmsConfigPitFmodeByGbar: saCmsPitFMode %d\r\n", saCmsPitFMode));
|
dprintf(("saCmsConfigPitFmodeByGbar: saCmsPitFMode %d\r\n", saCmsPitFMode));
|
||||||
|
@ -331,7 +331,7 @@ static long saCmsConfigPitFModeByGvar(displayPort_t *pDisp, const void *self)
|
||||||
if (saCmsPitFMode == 0) {
|
if (saCmsPitFMode == 0) {
|
||||||
// Bounce back
|
// Bounce back
|
||||||
saCmsPitFMode = 1;
|
saCmsPitFMode = 1;
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (saCmsPitFMode == 1) {
|
if (saCmsPitFMode == 1) {
|
||||||
|
@ -340,12 +340,12 @@ static long saCmsConfigPitFModeByGvar(displayPort_t *pDisp, const void *self)
|
||||||
saSetMode(SA_MODE_SET_OUT_RANGE_PITMODE);
|
saSetMode(SA_MODE_SET_OUT_RANGE_PITMODE);
|
||||||
}
|
}
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long saCmsConfigFreqModeByGvar(displayPort_t *pDisp, const void *self); // Forward
|
static const void *saCmsConfigFreqModeByGvar(displayPort_t *pDisp, const void *self); // Forward
|
||||||
|
|
||||||
static long saCmsConfigOpmodelByGvar(displayPort_t *pDisp, const void *self)
|
static const void *saCmsConfigOpmodelByGvar(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
@ -353,7 +353,7 @@ static long saCmsConfigOpmodelByGvar(displayPort_t *pDisp, const void *self)
|
||||||
if (saDevice.version == 1) {
|
if (saDevice.version == 1) {
|
||||||
if (saCmsOpmodel != SACMS_OPMODEL_FREE)
|
if (saCmsOpmodel != SACMS_OPMODEL_FREE)
|
||||||
saCmsOpmodel = SACMS_OPMODEL_FREE;
|
saCmsOpmodel = SACMS_OPMODEL_FREE;
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t opmodel = saCmsOpmodel;
|
uint8_t opmodel = saCmsOpmodel;
|
||||||
|
@ -382,7 +382,7 @@ static long saCmsConfigOpmodelByGvar(displayPort_t *pDisp, const void *self)
|
||||||
saCmsOpmodel = SACMS_OPMODEL_UNDEF + 1;
|
saCmsOpmodel = SACMS_OPMODEL_UNDEF + 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_EXTENDED_CMS_MENUS
|
#ifdef USE_EXTENDED_CMS_MENUS
|
||||||
|
@ -468,9 +468,9 @@ static const char * const saCmsPitNames[] = {
|
||||||
static OSD_TAB_t saCmsEntPitFMode = { &saCmsPitFMode, 1, saCmsPitFModeNames };
|
static OSD_TAB_t saCmsEntPitFMode = { &saCmsPitFMode, 1, saCmsPitFModeNames };
|
||||||
static OSD_TAB_t saCmsEntPit = {&saCmsPit, 2, saCmsPitNames};
|
static OSD_TAB_t saCmsEntPit = {&saCmsPit, 2, saCmsPitNames};
|
||||||
|
|
||||||
static long sacms_SetupTopMenu(void); // Forward
|
static const void *sacms_SetupTopMenu(void); // Forward
|
||||||
|
|
||||||
static long saCmsConfigFreqModeByGvar(displayPort_t *pDisp, const void *self)
|
static const void *saCmsConfigFreqModeByGvar(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
@ -486,10 +486,10 @@ static long saCmsConfigFreqModeByGvar(displayPort_t *pDisp, const void *self)
|
||||||
|
|
||||||
sacms_SetupTopMenu();
|
sacms_SetupTopMenu();
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long saCmsCommence(displayPort_t *pDisp, const void *self)
|
static const void *saCmsCommence(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
@ -540,28 +540,31 @@ static long saCmsCommence(displayPort_t *pDisp, const void *self)
|
||||||
return MENU_CHAIN_BACK;
|
return MENU_CHAIN_BACK;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long saCmsSetPORFreqOnEnter(void)
|
static const void *saCmsSetPORFreqOnEnter(void)
|
||||||
{
|
{
|
||||||
if (saDevice.version == 1)
|
if (saDevice.version == 1)
|
||||||
return MENU_CHAIN_BACK;
|
return MENU_CHAIN_BACK;
|
||||||
|
|
||||||
saCmsORFreqNew = saCmsORFreq;
|
saCmsORFreqNew = saCmsORFreq;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long saCmsSetPORFreq(displayPort_t *pDisp, const void *self)
|
static const void *saCmsSetPORFreq(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
saSetPitFreq(saCmsORFreqNew);
|
saSetPitFreq(saCmsORFreqNew);
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static char *saCmsORFreqGetString(void)
|
static const char *saCmsORFreqGetString(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
|
UNUSED(pDisp);
|
||||||
|
UNUSED(self);
|
||||||
|
|
||||||
static char pbuf[5];
|
static char pbuf[5];
|
||||||
|
|
||||||
tfp_sprintf(pbuf, "%4d", saCmsORFreq);
|
tfp_sprintf(pbuf, "%4d", saCmsORFreq);
|
||||||
|
@ -569,8 +572,11 @@ static char *saCmsORFreqGetString(void)
|
||||||
return pbuf;
|
return pbuf;
|
||||||
}
|
}
|
||||||
|
|
||||||
static char *saCmsUserFreqGetString(void)
|
static const char *saCmsUserFreqGetString(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
|
UNUSED(pDisp);
|
||||||
|
UNUSED(self);
|
||||||
|
|
||||||
static char pbuf[5];
|
static char pbuf[5];
|
||||||
|
|
||||||
tfp_sprintf(pbuf, "%4d", saCmsUserFreq);
|
tfp_sprintf(pbuf, "%4d", saCmsUserFreq);
|
||||||
|
@ -578,14 +584,14 @@ static char *saCmsUserFreqGetString(void)
|
||||||
return pbuf;
|
return pbuf;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long saCmsSetUserFreqOnEnter(void)
|
static const void *saCmsSetUserFreqOnEnter(void)
|
||||||
{
|
{
|
||||||
saCmsUserFreqNew = saCmsUserFreq;
|
saCmsUserFreqNew = saCmsUserFreq;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long saCmsConfigUserFreq(displayPort_t *pDisp, const void *self)
|
static const void *saCmsConfigUserFreq(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
@ -735,7 +741,7 @@ static const OSD_Entry saCmsMenuOfflineEntries[] =
|
||||||
|
|
||||||
CMS_Menu cmsx_menuVtxSmartAudio; // Forward
|
CMS_Menu cmsx_menuVtxSmartAudio; // Forward
|
||||||
|
|
||||||
static long sacms_SetupTopMenu(void)
|
static const void *sacms_SetupTopMenu(void)
|
||||||
{
|
{
|
||||||
if (saCmsDeviceStatus) {
|
if (saCmsDeviceStatus) {
|
||||||
if (saCmsFselModeNew == 0)
|
if (saCmsFselModeNew == 0)
|
||||||
|
@ -748,7 +754,7 @@ static long sacms_SetupTopMenu(void)
|
||||||
|
|
||||||
saCmsInitNames();
|
saCmsInitNames();
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
CMS_Menu cmsx_menuVtxSmartAudio = {
|
CMS_Menu cmsx_menuVtxSmartAudio = {
|
||||||
|
|
|
@ -100,7 +100,7 @@ static void trampCmsUpdateFreqRef(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static long trampCmsConfigBand(displayPort_t *pDisp, const void *self)
|
static const void *trampCmsConfigBand(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
@ -111,10 +111,10 @@ static long trampCmsConfigBand(displayPort_t *pDisp, const void *self)
|
||||||
else
|
else
|
||||||
trampCmsUpdateFreqRef();
|
trampCmsUpdateFreqRef();
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long trampCmsConfigChan(displayPort_t *pDisp, const void *self)
|
static const void *trampCmsConfigChan(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
@ -125,10 +125,10 @@ static long trampCmsConfigChan(displayPort_t *pDisp, const void *self)
|
||||||
else
|
else
|
||||||
trampCmsUpdateFreqRef();
|
trampCmsUpdateFreqRef();
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long trampCmsConfigPower(displayPort_t *pDisp, const void *self)
|
static const void *trampCmsConfigPower(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
@ -137,7 +137,7 @@ static long trampCmsConfigPower(displayPort_t *pDisp, const void *self)
|
||||||
// Bounce back
|
// Bounce back
|
||||||
trampCmsPower = 1;
|
trampCmsPower = 1;
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static OSD_INT16_t trampCmsEntTemp = { &trampTemperature, -100, 300, 0 };
|
static OSD_INT16_t trampCmsEntTemp = { &trampTemperature, -100, 300, 0 };
|
||||||
|
@ -148,7 +148,7 @@ static const char * const trampCmsPitModeNames[] = {
|
||||||
|
|
||||||
static OSD_TAB_t trampCmsEntPitMode = { &trampCmsPitMode, 2, trampCmsPitModeNames };
|
static OSD_TAB_t trampCmsEntPitMode = { &trampCmsPitMode, 2, trampCmsPitModeNames };
|
||||||
|
|
||||||
static long trampCmsSetPitMode(displayPort_t *pDisp, const void *self)
|
static const void *trampCmsSetPitMode(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
@ -160,10 +160,10 @@ static long trampCmsSetPitMode(displayPort_t *pDisp, const void *self)
|
||||||
trampSetPitMode(trampCmsPitMode - 1);
|
trampSetPitMode(trampCmsPitMode - 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long trampCmsCommence(displayPort_t *pDisp, const void *self)
|
static const void *trampCmsCommence(displayPort_t *pDisp, const void *self)
|
||||||
{
|
{
|
||||||
UNUSED(pDisp);
|
UNUSED(pDisp);
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
@ -220,13 +220,13 @@ static bool trampCmsInitSettings(void)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
static long trampCmsOnEnter(void)
|
static const void *trampCmsOnEnter(void)
|
||||||
{
|
{
|
||||||
if (!trampCmsInitSettings()) {
|
if (!trampCmsInitSettings()) {
|
||||||
return MENU_CHAIN_BACK;
|
return MENU_CHAIN_BACK;
|
||||||
}
|
}
|
||||||
|
|
||||||
return 0;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
static const OSD_Entry trampCmsMenuCommenceEntries[] = {
|
static const OSD_Entry trampCmsMenuCommenceEntries[] = {
|
||||||
|
|
|
@ -54,13 +54,13 @@ typedef enum
|
||||||
OME_MAX = OME_MENU
|
OME_MAX = OME_MENU
|
||||||
} OSD_MenuElement;
|
} OSD_MenuElement;
|
||||||
|
|
||||||
typedef long (*CMSEntryFuncPtr)(displayPort_t *displayPort, const void *ptr);
|
typedef const void *(*CMSEntryFuncPtr)(displayPort_t *displayPort, const void *ptr);
|
||||||
|
|
||||||
typedef struct
|
typedef struct
|
||||||
{
|
{
|
||||||
const char * const text;
|
const char * const text;
|
||||||
const OSD_MenuElement type;
|
const OSD_MenuElement type;
|
||||||
const CMSEntryFuncPtr func;
|
CMSEntryFuncPtr func;
|
||||||
void *data;
|
void *data;
|
||||||
const uint8_t flags;
|
const uint8_t flags;
|
||||||
} __attribute__((packed)) OSD_Entry;
|
} __attribute__((packed)) OSD_Entry;
|
||||||
|
@ -82,10 +82,11 @@ typedef struct
|
||||||
|
|
||||||
#define IS_DYNAMIC(p) ((p)->flags & DYNAMIC)
|
#define IS_DYNAMIC(p) ((p)->flags & DYNAMIC)
|
||||||
|
|
||||||
typedef long (*CMSMenuFuncPtr)(void);
|
typedef const void *(*CMSMenuFuncPtr)(void);
|
||||||
|
|
||||||
// Special return value(s) for function chaining by CMSMenuFuncPtr
|
// Special return value(s) for function chaining by CMSMenuFuncPtr
|
||||||
#define MENU_CHAIN_BACK (-1) // Causes automatic cmsMenuBack
|
extern int menuChainBack;
|
||||||
|
#define MENU_CHAIN_BACK (&menuChainBack) // Causes automatic cmsMenuBack
|
||||||
|
|
||||||
/*
|
/*
|
||||||
onExit function is called with self:
|
onExit function is called with self:
|
||||||
|
@ -94,11 +95,11 @@ onExit function is called with self:
|
||||||
(2) NULL if called from menu exit (forced exit at top level).
|
(2) NULL if called from menu exit (forced exit at top level).
|
||||||
*/
|
*/
|
||||||
|
|
||||||
typedef long (*CMSMenuOnExitPtr)(const OSD_Entry *self);
|
typedef const void *(*CMSMenuOnExitPtr)(const OSD_Entry *self);
|
||||||
|
|
||||||
typedef const void * (*CMSMenuCheckRedirectPtr)(void);
|
typedef const void * (*CMSMenuCheckRedirectPtr)(void);
|
||||||
|
|
||||||
typedef long (*CMSMenuOnDisplayUpdatePtr)(const OSD_Entry *selected);
|
typedef const void *(*CMSMenuOnDisplayUpdatePtr)(const OSD_Entry *selected);
|
||||||
|
|
||||||
typedef struct
|
typedef struct
|
||||||
{
|
{
|
||||||
|
@ -165,7 +166,3 @@ typedef struct
|
||||||
{
|
{
|
||||||
char *val;
|
char *val;
|
||||||
} OSD_String_t;
|
} OSD_String_t;
|
||||||
|
|
||||||
// This is a function used in the func member if the type is OME_Submenu.
|
|
||||||
|
|
||||||
typedef char * (*CMSMenuOptFuncPtr)(void);
|
|
||||||
|
|
|
@ -680,5 +680,5 @@
|
||||||
|
|
||||||
// XXX Tentative; may be removed
|
// XXX Tentative; may be removed
|
||||||
#if defined(USE_MSP_DISPLAYPORT) && defined(USE_OSD_OVER_MSP_DISPLAYPORT)
|
#if defined(USE_MSP_DISPLAYPORT) && defined(USE_OSD_OVER_MSP_DISPLAYPORT)
|
||||||
#define USE_DISPLAYPORT_MSP_VENDOR_SPECIFIC
|
//#define USE_DISPLAYPORT_MSP_VENDOR_SPECIFIC
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -33,7 +33,7 @@ extern "C" {
|
||||||
#include "fc/rc_modes.h"
|
#include "fc/rc_modes.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
void cmsMenuOpen(void);
|
void cmsMenuOpen(void);
|
||||||
long cmsMenuBack(displayPort_t *pDisplay);
|
const void *cmsMenuBack(displayPort_t *pDisplay);
|
||||||
uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key);
|
uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key);
|
||||||
extern CMS_Menu *currentMenu; // Points to top entry of the current page
|
extern CMS_Menu *currentMenu; // Points to top entry of the current page
|
||||||
}
|
}
|
||||||
|
@ -71,8 +71,8 @@ TEST(CMSUnittest, TestCmsMenuExit0)
|
||||||
cmsDisplayPortRegister(displayPort);
|
cmsDisplayPortRegister(displayPort);
|
||||||
|
|
||||||
cmsMenuOpen();
|
cmsMenuOpen();
|
||||||
long exit = cmsMenuExit(displayPort, (void*)0);
|
const void *exit = cmsMenuExit(displayPort, (void*)0);
|
||||||
EXPECT_EQ(0, exit);
|
EXPECT_EQ(NULL, exit);
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST(CMSUnittest, TestCmsMenuExit1)
|
TEST(CMSUnittest, TestCmsMenuExit1)
|
||||||
|
@ -82,8 +82,8 @@ TEST(CMSUnittest, TestCmsMenuExit1)
|
||||||
cmsDisplayPortRegister(displayPort);
|
cmsDisplayPortRegister(displayPort);
|
||||||
|
|
||||||
cmsMenuOpen();
|
cmsMenuOpen();
|
||||||
long exit = cmsMenuExit(displayPort, (void*)0);
|
const void *exit = cmsMenuExit(displayPort, (void*)0);
|
||||||
EXPECT_EQ(0, exit);
|
EXPECT_EQ(NULL, exit);
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST(CMSUnittest, TestCmsMenuBack)
|
TEST(CMSUnittest, TestCmsMenuBack)
|
||||||
|
@ -93,8 +93,8 @@ TEST(CMSUnittest, TestCmsMenuBack)
|
||||||
cmsDisplayPortRegister(displayPort);
|
cmsDisplayPortRegister(displayPort);
|
||||||
|
|
||||||
cmsMenuOpen();
|
cmsMenuOpen();
|
||||||
long exit = cmsMenuBack(displayPort);
|
const void *exit = cmsMenuBack(displayPort);
|
||||||
EXPECT_EQ(0, exit);
|
EXPECT_EQ(NULL, exit);
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST(CMSUnittest, TestCmsMenuKey)
|
TEST(CMSUnittest, TestCmsMenuKey)
|
||||||
|
|
Loading…
Reference in New Issue