mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 20:35:33 +03:00
Improvements from review.
This commit is contained in:
parent
31830dc10c
commit
1b98b1e2aa
5 changed files with 45 additions and 45 deletions
|
@ -160,7 +160,7 @@ static uint8_t leftMenuColumn;
|
|||
static uint8_t rightMenuColumn;
|
||||
static uint8_t maxMenuItems;
|
||||
static uint8_t linesPerMenuItem;
|
||||
static uint8_t externKey = CMS_KEY_NONE;
|
||||
static cms_key_e externKey = CMS_KEY_NONE;
|
||||
|
||||
bool cmsInMenu = false;
|
||||
|
||||
|
@ -768,7 +768,7 @@ long cmsMenuExit(displayPort_t *pDisplay, const void *ptr)
|
|||
#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;
|
||||
|
@ -974,13 +974,13 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
|
|||
return res;
|
||||
}
|
||||
|
||||
void cmsSetExternKey(uint8_t extKey)
|
||||
void cmsSetExternKey(cms_key_e extKey)
|
||||
{
|
||||
if (externKey == CMS_KEY_NONE)
|
||||
externKey = extKey;
|
||||
}
|
||||
|
||||
uint16_t cmsHandleKeyWithRepeat(displayPort_t *pDisplay, uint8_t key, int repeatCount)
|
||||
uint16_t cmsHandleKeyWithRepeat(displayPort_t *pDisplay, cms_key_e key, int repeatCount)
|
||||
{
|
||||
uint16_t ret = 0;
|
||||
|
||||
|
@ -1025,7 +1025,7 @@ void cmsUpdate(uint32_t currentTimeUs)
|
|||
// Scan 'key' first
|
||||
//
|
||||
|
||||
uint8_t key = CMS_KEY_NONE;
|
||||
cms_key_e key = CMS_KEY_NONE;
|
||||
|
||||
if (externKey != CMS_KEY_NONE) {
|
||||
rcDelayMs = cmsHandleKey(pCurrentDisplay, externKey);
|
||||
|
|
|
@ -24,13 +24,15 @@
|
|||
|
||||
#include "common/time.h"
|
||||
|
||||
#define CMS_KEY_NONE 0
|
||||
#define CMS_KEY_UP 1
|
||||
#define CMS_KEY_DOWN 2
|
||||
#define CMS_KEY_LEFT 3
|
||||
#define CMS_KEY_RIGHT 4
|
||||
#define CMS_KEY_ESC 5
|
||||
#define CMS_KEY_MENU 6
|
||||
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;
|
||||
|
||||
|
|
|
@ -49,21 +49,13 @@ static int hottWriteChar(displayPort_t *displayPort, uint8_t col, uint8_t row, u
|
|||
{
|
||||
UNUSED(displayPort);
|
||||
|
||||
|
||||
// Correct fake display dimensions
|
||||
if (row <= ROW_CORRECTION - 1)
|
||||
if (row < ROW_CORRECTION || row >= HOTT_TEXTMODE_DISPLAY_ROWS + ROW_CORRECTION
|
||||
|| col < COL_CORRECTION || col >= HOTT_TEXTMODE_DISPLAY_COLUMNS + COL_CORRECTION) {
|
||||
return 0;
|
||||
else
|
||||
}
|
||||
row -= ROW_CORRECTION;
|
||||
|
||||
if (col <= COL_CORRECTION - 1)
|
||||
return 0;
|
||||
else
|
||||
col -= COL_CORRECTION;
|
||||
|
||||
if (row >= HOTT_TEXTMODE_DISPLAY_ROWS || col >= HOTT_TEXTMODE_DISPLAY_COLUMNS)
|
||||
return 0;
|
||||
|
||||
hottTextmodeWriteChar(col, row, c);
|
||||
return 0;
|
||||
}
|
||||
|
@ -94,8 +86,9 @@ static bool hottIsTransferInProgress(const displayPort_t *displayPort)
|
|||
|
||||
static int hottHeartbeat(displayPort_t *displayPort)
|
||||
{
|
||||
if (!hottTextmodeIsAlive())
|
||||
if (!hottTextmodeIsAlive()) {
|
||||
cmsMenuExit(displayPort, (void*)CMS_EXIT_SAVE);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
@ -156,7 +149,7 @@ void hottCmsOpen()
|
|||
}
|
||||
}
|
||||
|
||||
void hottSetCmsKey(uint8_t hottKey, bool esc)
|
||||
void hottSetCmsKey(uint8_t hottKey, bool keepCmsOpen)
|
||||
{
|
||||
switch (hottKey) {
|
||||
case HOTTV4_BUTTON_DEC:
|
||||
|
@ -166,8 +159,9 @@ void hottSetCmsKey(uint8_t hottKey, bool esc)
|
|||
cmsSetExternKey(CMS_KEY_DOWN);
|
||||
break;
|
||||
case HOTTV4_BUTTON_SET:
|
||||
if (cmsInMenu)
|
||||
if (cmsInMenu) {
|
||||
cmsMenuExit(pCurrentDisplay, (void*)CMS_EXIT_SAVE);
|
||||
}
|
||||
cmsSetExternKey(CMS_KEY_NONE);
|
||||
break;
|
||||
case HOTTV4_BUTTON_NEXT:
|
||||
|
@ -175,8 +169,9 @@ void hottSetCmsKey(uint8_t hottKey, bool esc)
|
|||
break;
|
||||
case HOTTV4_BUTTON_PREV:
|
||||
cmsSetExternKey(CMS_KEY_LEFT);
|
||||
if (esc)
|
||||
if (keepCmsOpen) { // Make sure CMS is open until textmode is closed.
|
||||
cmsMenuOpen();
|
||||
}
|
||||
break;
|
||||
default:
|
||||
cmsSetExternKey(CMS_KEY_NONE);
|
||||
|
|
|
@ -92,6 +92,7 @@
|
|||
#include "scheduler/scheduler.h"
|
||||
#include "io/displayport_hott.h"
|
||||
|
||||
#define HOTT_TEXTMODE_TASK_PERIOD 1000
|
||||
#define HOTT_TEXTMODE_RX_SCHEDULE 5000
|
||||
#define HOTT_TEXTMODE_TX_DELAY_US 1000
|
||||
#endif
|
||||
|
@ -131,11 +132,11 @@ static HOTT_GPS_MSG_t hottGPSMessage;
|
|||
static HOTT_EAM_MSG_t hottEAMMessage;
|
||||
|
||||
#if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
|
||||
static HOTT_TEXTMODE_MSG_t hottTextModeMessage;
|
||||
static hottTextModeMsg_t hottTextModeMessage;
|
||||
static bool textmodeIsAlive = false;
|
||||
static int32_t telemetryPeriod = 0;
|
||||
static int32_t telemetryTaskPeriod = 0;
|
||||
|
||||
static void initialiseTextmodeMessage(HOTT_TEXTMODE_MSG_t *msg)
|
||||
static void initialiseTextmodeMessage(hottTextModeMsg_t *msg)
|
||||
{
|
||||
msg->start = HOTT_TEXTMODE_START;
|
||||
msg->esc = HOTT_EAM_SENSOR_TEXT_ID;
|
||||
|
@ -450,8 +451,8 @@ static void hottTextmodeStart()
|
|||
// Increase menu speed
|
||||
cfTaskInfo_t taskInfo;
|
||||
getTaskInfo(TASK_TELEMETRY, &taskInfo);
|
||||
telemetryPeriod = taskInfo.desiredPeriod;
|
||||
rescheduleTask(TASK_TELEMETRY, TASK_PERIOD_HZ(1000));
|
||||
telemetryTaskPeriod = taskInfo.desiredPeriod;
|
||||
rescheduleTask(TASK_TELEMETRY, TASK_PERIOD_HZ(HOTT_TEXTMODE_TASK_PERIOD));
|
||||
|
||||
rxSchedule = HOTT_TEXTMODE_RX_SCHEDULE;
|
||||
txDelayUs = HOTT_TEXTMODE_TX_DELAY_US;
|
||||
|
@ -460,8 +461,9 @@ static void hottTextmodeStart()
|
|||
static void hottTextmodeStop()
|
||||
{
|
||||
// Set back to avoid slow down of the FC
|
||||
if (telemetryPeriod > 0)
|
||||
rescheduleTask(TASK_TELEMETRY, telemetryPeriod);
|
||||
if (telemetryTaskPeriod > 0) {
|
||||
rescheduleTask(TASK_TELEMETRY, telemetryTaskPeriod);
|
||||
}
|
||||
|
||||
rxSchedule = HOTT_RX_SCHEDULE;
|
||||
txDelayUs = HOTT_TX_DELAY_US;
|
||||
|
@ -494,24 +496,25 @@ static void processHottTextModeRequest(const uint8_t cmd)
|
|||
{
|
||||
static bool setEscBack = false;
|
||||
|
||||
if (!textmodeIsAlive)
|
||||
{
|
||||
if (!textmodeIsAlive) {
|
||||
hottTextmodeStart();
|
||||
textmodeIsAlive = true;
|
||||
}
|
||||
|
||||
if ((cmd & 0xF0) != HOTT_EAM_SENSOR_TEXT_ID)
|
||||
if ((cmd & 0xF0) != HOTT_EAM_SENSOR_TEXT_ID) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (setEscBack) {
|
||||
hottTextModeMessage.esc = HOTT_EAM_SENSOR_TEXT_ID;
|
||||
setEscBack = false;
|
||||
}
|
||||
|
||||
if (hottTextModeMessage.esc != HOTT_TEXTMODE_ESC)
|
||||
if (hottTextModeMessage.esc != HOTT_TEXTMODE_ESC) {
|
||||
hottCmsOpen();
|
||||
else
|
||||
} else {
|
||||
setEscBack = true;
|
||||
}
|
||||
|
||||
hottSetCmsKey(cmd & 0x0f, hottTextModeMessage.esc == HOTT_TEXTMODE_ESC);
|
||||
hottSendResponse((uint8_t *)&hottTextModeMessage, sizeof(hottTextModeMessage));
|
||||
|
|
|
@ -112,7 +112,7 @@ typedef enum {
|
|||
#define HOTT_TEXTMODE_STOP 0x7D
|
||||
#define HOTT_TEXTMODE_ESC 0x01
|
||||
//Text mode msgs type
|
||||
typedef struct HOTT_TEXTMODE_MSG_s {
|
||||
typedef struct hottTextModeMsg_s {
|
||||
uint8_t start; //#01 constant value 0x7b
|
||||
uint8_t esc; //#02 Low byte: Sensor ID or 0x01 for escape
|
||||
uint8_t warning; //#03 1=A 2=B ...
|
||||
|
@ -120,7 +120,7 @@ typedef struct HOTT_TEXTMODE_MSG_s {
|
|||
// Bit 7 = 1 -> Inverse character display
|
||||
// Display 21x8
|
||||
uint8_t stop; //#171 constant value 0x7d
|
||||
} HOTT_TEXTMODE_MSG_t;
|
||||
} hottTextModeMsg_t;
|
||||
|
||||
typedef struct HOTT_GAM_MSG_s {
|
||||
uint8_t start_byte; //#01 start uint8_t constant value 0x7c
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue