Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

CMS for HoTT-Textmode. #6224

Merged
merged 4 commits into from
Aug 16, 2018
Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions make/source.mk
Original file line number Diff line number Diff line change
Expand Up @@ -143,6 +143,7 @@ FC_SRC = \
io/displayport_oled.c \
io/displayport_srxl.c \
io/displayport_crsf.c \
io/displayport_hott.c \
io/rcdevice_cam.c \
io/rcdevice.c \
io/gps.c \
Expand Down
160 changes: 82 additions & 78 deletions src/main/cms/cms.c
Original file line number Diff line number Diff line change
Expand Up @@ -160,6 +160,7 @@ static uint8_t leftMenuColumn;
static uint8_t rightMenuColumn;
static uint8_t maxMenuItems;
static uint8_t linesPerMenuItem;
static cms_key_e externKey = CMS_KEY_NONE;

bool cmsInMenu = false;

Expand Down Expand Up @@ -764,36 +765,28 @@ long cmsMenuExit(displayPort_t *pDisplay, const void *ptr)
#define IS_LO(X) (rcData[X] < 1250)
#define IS_MID(X) (rcData[X] > 1250 && rcData[X] < 1750)

#define KEY_NONE 0
#define KEY_UP 1
#define KEY_DOWN 2
#define KEY_LEFT 3
#define KEY_RIGHT 4
#define KEY_ESC 5
#define KEY_MENU 6

#define BUTTON_TIME 250 // msec
#define BUTTON_PAUSE 500 // msec

STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, cms_key_e key)
{
uint16_t res = BUTTON_TIME;
OSD_Entry *p;

if (!currentCtx.menu)
return res;

if (key == KEY_MENU) {
if (key == CMS_KEY_MENU) {
cmsMenuOpen();
return BUTTON_PAUSE;
}

if (key == KEY_ESC) {
if (key == CMS_KEY_ESC) {
cmsMenuBack(pDisplay);
return BUTTON_PAUSE;
}

if (key == KEY_DOWN) {
if (key == CMS_KEY_DOWN) {
if (currentCtx.cursorRow < pageMaxRow) {
currentCtx.cursorRow++;
} else {
Expand All @@ -802,7 +795,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
}
}

if (key == KEY_UP) {
if (key == CMS_KEY_UP) {
currentCtx.cursorRow--;

// Skip non-title labels
Expand All @@ -816,22 +809,22 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
}
}

if (key == KEY_DOWN || key == KEY_UP)
if (key == CMS_KEY_DOWN || key == CMS_KEY_UP)
return res;

p = pageTop + currentCtx.cursorRow;

switch (p->type) {
case OME_Submenu:
if (key == KEY_RIGHT) {
if (key == CMS_KEY_RIGHT) {
cmsMenuChange(pDisplay, p->data);
res = BUTTON_PAUSE;
}
break;

case OME_Funcall:;
long retval;
if (p->func && key == KEY_RIGHT) {
if (p->func && key == CMS_KEY_RIGHT) {
retval = p->func(pDisplay, p->data);
if (retval == MENU_CHAIN_BACK)
cmsMenuBack(pDisplay);
Expand All @@ -840,7 +833,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
break;

case OME_OSD_Exit:
if (p->func && key == KEY_RIGHT) {
if (p->func && key == CMS_KEY_RIGHT) {
p->func(pDisplay, p->data);
res = BUTTON_PAUSE;
}
Expand All @@ -854,7 +847,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
case OME_Bool:
if (p->data) {
uint8_t *val = p->data;
if (key == KEY_RIGHT)
if (key == CMS_KEY_RIGHT)
*val = 1;
else
*val = 0;
Expand All @@ -867,7 +860,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
if (p->data) {
uint16_t *val = (uint16_t *)p->data;

if (key == KEY_RIGHT)
if (key == CMS_KEY_RIGHT)
*val |= VISIBLE_FLAG;
else
*val %= ~VISIBLE_FLAG;
Expand All @@ -880,7 +873,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
case OME_FLOAT:
if (p->data) {
OSD_UINT8_t *ptr = p->data;
if (key == KEY_RIGHT) {
if (key == CMS_KEY_RIGHT) {
if (*ptr->val < ptr->max)
*ptr->val += ptr->step;
}
Expand All @@ -899,7 +892,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
if (p->type == OME_TAB) {
OSD_TAB_t *ptr = p->data;

if (key == KEY_RIGHT) {
if (key == CMS_KEY_RIGHT) {
if (*ptr->val < ptr->max)
*ptr->val += 1;
}
Expand All @@ -916,7 +909,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
case OME_INT8:
if (p->data) {
OSD_INT8_t *ptr = p->data;
if (key == KEY_RIGHT) {
if (key == CMS_KEY_RIGHT) {
if (*ptr->val < ptr->max)
*ptr->val += ptr->step;
}
Expand All @@ -934,7 +927,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
case OME_UINT16:
if (p->data) {
OSD_UINT16_t *ptr = p->data;
if (key == KEY_RIGHT) {
if (key == CMS_KEY_RIGHT) {
if (*ptr->val < ptr->max)
*ptr->val += ptr->step;
}
Expand All @@ -952,7 +945,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
case OME_INT16:
if (p->data) {
OSD_INT16_t *ptr = p->data;
if (key == KEY_RIGHT) {
if (key == CMS_KEY_RIGHT) {
if (*ptr->val < ptr->max)
*ptr->val += ptr->step;
}
Expand Down Expand Up @@ -981,7 +974,13 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
return res;
}

uint16_t cmsHandleKeyWithRepeat(displayPort_t *pDisplay, uint8_t key, int repeatCount)
void cmsSetExternKey(cms_key_e extKey)
{
if (externKey == CMS_KEY_NONE)
externKey = extKey;
}
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Always use { } for if, while, etc. it has easy maintenance in the future.


uint16_t cmsHandleKeyWithRepeat(displayPort_t *pDisplay, cms_key_e key, int repeatCount)
{
uint16_t ret = 0;

Expand Down Expand Up @@ -1026,72 +1025,77 @@ void cmsUpdate(uint32_t currentTimeUs)
// Scan 'key' first
//

uint8_t key = KEY_NONE;

if (IS_MID(THROTTLE) && IS_LO(YAW) && IS_HI(PITCH) && !ARMING_FLAG(ARMED)) {
key = KEY_MENU;
}
else if (IS_HI(PITCH)) {
key = KEY_UP;
}
else if (IS_LO(PITCH)) {
key = KEY_DOWN;
}
else if (IS_LO(ROLL)) {
key = KEY_LEFT;
}
else if (IS_HI(ROLL)) {
key = KEY_RIGHT;
}
else if (IS_HI(YAW) || IS_LO(YAW))
{
key = KEY_ESC;
}
cms_key_e key = CMS_KEY_NONE;

if (key == KEY_NONE) {
// No 'key' pressed, reset repeat control
holdCount = 1;
repeatCount = 1;
repeatBase = 0;
if (externKey != CMS_KEY_NONE) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

IMO current stick-key handling code should be separated into own function(s) (cmsProcessStickKey? cmsUpdateStickKey? )
and then

  if (externKey != CMS_KEY_NONE) {
    delay = cmsHandleKey(pCurrentDisplay, externKey);
    cmsProcessStickKeyReset(delay);
    externKey = CMS_KEY_NONE;
  } else {
   cmsProcessStickKey();
  }

current function is getting too complicated (it would be ideal to separate stick-key mapping from repeat)

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, but what should a cmsProcessStickKeyReset do?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

it should probably be cmsProcessStickKeyStop - stop autorepeat, do nothing until stick position is CMS_KEY_NONE.
And set rcDelayMs if sticks are centered ...

Copy link
Contributor Author

@Scavanger Scavanger Jun 27, 2018

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I agree, but I think this has more to do with refactoring the CMS, and not with HoTT Textmode.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, but these problems were quite localized and hidden until this PR ...
The code was far from ideal, this PR is exposing its design flaws

rcDelayMs = cmsHandleKey(pCurrentDisplay, externKey);
externKey = CMS_KEY_NONE;
} else {
// The 'key' is being pressed; keep counting
++holdCount;
}
if (IS_MID(THROTTLE) && IS_LO(YAW) && IS_HI(PITCH) && !ARMING_FLAG(ARMED)) {
key = CMS_KEY_MENU;
}
else if (IS_HI(PITCH)) {
key = CMS_KEY_UP;
}
else if (IS_LO(PITCH)) {
key = CMS_KEY_DOWN;
}
else if (IS_LO(ROLL)) {
key = CMS_KEY_LEFT;
}
else if (IS_HI(ROLL)) {
key = CMS_KEY_RIGHT;
}
else if (IS_HI(YAW) || IS_LO(YAW))
{
key = CMS_KEY_ESC;
}

if (key == CMS_KEY_NONE) {
// No 'key' pressed, reset repeat control
holdCount = 1;
repeatCount = 1;
repeatBase = 0;
} else {
// The 'key' is being pressed; keep counting
++holdCount;
}

if (rcDelayMs > 0) {
rcDelayMs -= (currentTimeMs - lastCalledMs);
} else if (key) {
rcDelayMs = cmsHandleKeyWithRepeat(pCurrentDisplay, key, repeatCount);
if (rcDelayMs > 0) {
rcDelayMs -= (currentTimeMs - lastCalledMs);
} else if (key) {
rcDelayMs = cmsHandleKeyWithRepeat(pCurrentDisplay, key, repeatCount);

// Key repeat effect is implemented in two phases.
// First phldase is to decrease rcDelayMs reciprocal to hold time.
// When rcDelayMs reached a certain limit (scheduling interval),
// repeat rate will not raise anymore, so we call key handler
// multiple times (repeatCount).
//
// XXX Caveat: Most constants are adjusted pragmatically.
// XXX Rewrite this someday, so it uses actual hold time instead
// of holdCount, which depends on the scheduling interval.
// Key repeat effect is implemented in two phases.
// First phldase is to decrease rcDelayMs reciprocal to hold time.
// When rcDelayMs reached a certain limit (scheduling interval),
// repeat rate will not raise anymore, so we call key handler
// multiple times (repeatCount).
//
// XXX Caveat: Most constants are adjusted pragmatically.
// XXX Rewrite this someday, so it uses actual hold time instead
// of holdCount, which depends on the scheduling interval.

if (((key == KEY_LEFT) || (key == KEY_RIGHT)) && (holdCount > 20)) {
if (((key == CMS_KEY_LEFT) || (key == CMS_KEY_RIGHT)) && (holdCount > 20)) {

// Decrease rcDelayMs reciprocally
// Decrease rcDelayMs reciprocally

rcDelayMs /= (holdCount - 20);
rcDelayMs /= (holdCount - 20);

// When we reach the scheduling limit,
// When we reach the scheduling limit,

if (rcDelayMs <= 50) {
if (rcDelayMs <= 50) {

// start calling handler multiple times.
// start calling handler multiple times.

if (repeatBase == 0)
repeatBase = holdCount;
if (repeatBase == 0)
repeatBase = holdCount;

repeatCount = repeatCount + (holdCount - repeatBase) / 5;
repeatCount = repeatCount + (holdCount - repeatBase) / 5;

if (repeatCount > 5) {
repeatCount= 5;
if (repeatCount > 5) {
repeatCount= 5;
}
}
}
}
Expand Down
11 changes: 11 additions & 0 deletions src/main/cms/cms.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,16 @@

#include "common/time.h"

typedef enum {
CMS_KEY_NONE,
CMS_KEY_UP,
CMS_KEY_DOWN,
CMS_KEY_LEFT,
CMS_KEY_RIGHT,
CMS_KEY_ESC,
CMS_KEY_MENU
} cms_key_e;

extern bool cmsInMenu;

// Device management
Expand All @@ -39,6 +49,7 @@ void cmsMenuOpen(void);
long cmsMenuChange(displayPort_t *pPort, const void *ptr);
long cmsMenuExit(displayPort_t *pPort, const void *ptr);
void cmsUpdate(uint32_t currentTimeUs);
void cmsSetExternKey(cms_key_e extKey);

#define CMS_STARTUP_HELP_TEXT1 "MENU:THR MID"
#define CMS_STARTUP_HELP_TEXT2 "+ YAW LEFT"
Expand Down
5 changes: 5 additions & 0 deletions src/main/fc/fc_init.c
Original file line number Diff line number Diff line change
Expand Up @@ -112,6 +112,7 @@
#include "io/beeper.h"
#include "io/displayport_max7456.h"
#include "io/displayport_srxl.h"
#include "io/displayport_hott.h"
#include "io/displayport_crsf.h"
#include "io/serial.h"
#include "io/flashfs.h"
Expand Down Expand Up @@ -607,6 +608,10 @@ void init(void)
cmsDisplayPortRegister(displayPortCrsfInit());
#endif

#if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
cmsDisplayPortRegister(displayPortHottInit());
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Might want to register this outside of fc/fc_init.c and instead in the telemetry subsystem. Don't want to register multiple display ports and cause unwanted cycling between them when people aren't using the protocol or have telemetry enabled.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I am doing the same for CMS over CRSF.

#endif

#ifdef USE_GPS
if (feature(FEATURE_GPS)) {
gpsInit();
Expand Down
Loading