Merge pull request #9981 from mikeller/fix_max7456_delay_problems

Fixed the MAX7456 loop time problems introduced by #9948.
This commit is contained in:
Michael Keller 2020-07-26 15:31:16 +12:00 committed by GitHub
commit 94cd650472
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
18 changed files with 118 additions and 96 deletions

View File

@ -797,6 +797,10 @@ void cmsMenuOpen(void)
} }
} }
displayGrab(pCurrentDisplay); // grab the display for use by the CMS displayGrab(pCurrentDisplay); // grab the display for use by the CMS
// FIXME this should probably not have a dependency on the OSD or OSD slave code
#ifdef USE_OSD
resumeRefreshAt = 0;
#endif
if ( pCurrentDisplay->cols < NORMAL_SCREEN_MIN_COLS) { if ( pCurrentDisplay->cols < NORMAL_SCREEN_MIN_COLS) {
smallScreen = true; smallScreen = true;
@ -875,7 +879,8 @@ const void *cmsMenuExit(displayPort_t *pDisplay, const void *ptr)
displayClearScreen(pDisplay); displayClearScreen(pDisplay);
displayWrite(pDisplay, 5, 3, DISPLAYPORT_ATTR_NONE, "REBOOTING..."); displayWrite(pDisplay, 5, 3, DISPLAYPORT_ATTR_NONE, "REBOOTING...");
displayResync(pDisplay); // Was max7456RefreshAll(); why at this timing? // Flush display
displayRedraw(pDisplay);
stopMotors(); stopMotors();
motorShutdown(); motorShutdown();

View File

@ -171,16 +171,17 @@ static const void *cmsx_EraseFlash(displayPort_t *pDisplay, const void *ptr)
displayClearScreen(pDisplay); displayClearScreen(pDisplay);
displayWrite(pDisplay, 5, 3, DISPLAYPORT_ATTR_INFO, "ERASING FLASH..."); displayWrite(pDisplay, 5, 3, DISPLAYPORT_ATTR_INFO, "ERASING FLASH...");
displayResync(pDisplay); // Was max7456RefreshAll(); Why at this timing? displayRedraw(pDisplay);
flashfsEraseCompletely(); flashfsEraseCompletely();
while (!flashfsIsReady()) { while (!flashfsIsReady()) {
//TODO: Make this non-blocking!
delay(100); delay(100);
} }
beeper(BEEPER_BLACKBOX_ERASE); beeper(BEEPER_BLACKBOX_ERASE);
displayClearScreen(pDisplay); displayClearScreen(pDisplay);
displayResync(pDisplay); // Was max7456RefreshAll(); wedges during heavy SPI? displayRedraw(pDisplay);
// 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();

View File

@ -108,9 +108,9 @@ void displayHeartbeat(displayPort_t *instance)
instance->vTable->heartbeat(instance); instance->vTable->heartbeat(instance);
} }
void displayResync(displayPort_t *instance) void displayRedraw(displayPort_t *instance)
{ {
instance->vTable->resync(instance); instance->vTable->redraw(instance);
} }
uint16_t displayTxBytesFree(const displayPort_t *instance) uint16_t displayTxBytesFree(const displayPort_t *instance)
@ -153,12 +153,12 @@ bool displayWriteFontCharacter(displayPort_t *instance, uint16_t addr, const osd
return false; return false;
} }
bool displayIsReady(displayPort_t *instance) bool displayCheckReady(displayPort_t *instance, bool rescan)
{ {
if (instance->vTable->isReady) { if (instance->vTable->checkReady) {
return instance->vTable->isReady(instance); return instance->vTable->checkReady(instance, rescan);
} }
// Drivers that don't provide an isReady method are // Drivers that don't provide a checkReady method are
// assumed to be immediately ready (either by actually // assumed to be immediately ready (either by actually
// begin ready very quickly or by blocking) // begin ready very quickly or by blocking)
return true; return true;

View File

@ -74,14 +74,14 @@ typedef struct displayPortVTable_s {
int (*writeChar)(displayPort_t *displayPort, uint8_t x, uint8_t y, uint8_t attr, uint8_t c); int (*writeChar)(displayPort_t *displayPort, uint8_t x, uint8_t y, uint8_t attr, uint8_t c);
bool (*isTransferInProgress)(const displayPort_t *displayPort); bool (*isTransferInProgress)(const displayPort_t *displayPort);
int (*heartbeat)(displayPort_t *displayPort); int (*heartbeat)(displayPort_t *displayPort);
void (*resync)(displayPort_t *displayPort); void (*redraw)(displayPort_t *displayPort);
bool (*isSynced)(const displayPort_t *displayPort); bool (*isSynced)(const displayPort_t *displayPort);
uint32_t (*txBytesFree)(const displayPort_t *displayPort); uint32_t (*txBytesFree)(const displayPort_t *displayPort);
bool (*layerSupported)(displayPort_t *displayPort, displayPortLayer_e layer); bool (*layerSupported)(displayPort_t *displayPort, displayPortLayer_e layer);
bool (*layerSelect)(displayPort_t *displayPort, displayPortLayer_e layer); bool (*layerSelect)(displayPort_t *displayPort, displayPortLayer_e layer);
bool (*layerCopy)(displayPort_t *displayPort, displayPortLayer_e destLayer, displayPortLayer_e sourceLayer); bool (*layerCopy)(displayPort_t *displayPort, displayPortLayer_e destLayer, displayPortLayer_e sourceLayer);
bool (*writeFontCharacter)(displayPort_t *instance, uint16_t addr, const struct osdCharacter_s *chr); bool (*writeFontCharacter)(displayPort_t *instance, uint16_t addr, const struct osdCharacter_s *chr);
bool (*isReady)(displayPort_t *displayPort); bool (*checkReady)(displayPort_t *displayPort, bool rescan);
void (*beginTransaction)(displayPort_t *displayPort, displayTransactionOption_e opts); void (*beginTransaction)(displayPort_t *displayPort, displayTransactionOption_e opts);
void (*commitTransaction)(displayPort_t *displayPort); void (*commitTransaction)(displayPort_t *displayPort);
bool (*getCanvas)(struct displayCanvas_s *canvas, const displayPort_t *displayPort); bool (*getCanvas)(struct displayCanvas_s *canvas, const displayPort_t *displayPort);
@ -99,11 +99,11 @@ int displayWrite(displayPort_t *instance, uint8_t x, uint8_t y, uint8_t attr, co
int displayWriteChar(displayPort_t *instance, uint8_t x, uint8_t y, uint8_t attr, uint8_t c); int displayWriteChar(displayPort_t *instance, uint8_t x, uint8_t y, uint8_t attr, uint8_t c);
bool displayIsTransferInProgress(const displayPort_t *instance); bool displayIsTransferInProgress(const displayPort_t *instance);
void displayHeartbeat(displayPort_t *instance); void displayHeartbeat(displayPort_t *instance);
void displayResync(displayPort_t *instance); void displayRedraw(displayPort_t *instance);
bool displayIsSynced(const displayPort_t *instance); bool displayIsSynced(const displayPort_t *instance);
uint16_t displayTxBytesFree(const displayPort_t *instance); uint16_t displayTxBytesFree(const displayPort_t *instance);
bool displayWriteFontCharacter(displayPort_t *instance, uint16_t addr, const struct osdCharacter_s *chr); bool displayWriteFontCharacter(displayPort_t *instance, uint16_t addr, const struct osdCharacter_s *chr);
bool displayIsReady(displayPort_t *instance); bool displayCheckReady(displayPort_t *instance, bool rescan);
void displayBeginTransaction(displayPort_t *instance, displayTransactionOption_e opts); void displayBeginTransaction(displayPort_t *instance, displayTransactionOption_e opts);
void displayCommitTransaction(displayPort_t *instance); void displayCommitTransaction(displayPort_t *instance);
bool displayGetCanvas(struct displayCanvas_s *canvas, const displayPort_t *instance); bool displayGetCanvas(struct displayCanvas_s *canvas, const displayPort_t *instance);

View File

@ -956,8 +956,7 @@ void init(void)
#if defined(USE_MAX7456) #if defined(USE_MAX7456)
case OSD_DISPLAYPORT_DEVICE_MAX7456: case OSD_DISPLAYPORT_DEVICE_MAX7456:
// If there is a max7456 chip for the OSD configured and detectd then use it. // If there is a max7456 chip for the OSD configured and detectd then use it.
osdDisplayPort = max7456DisplayPortInit(vcdProfile()); if (max7456DisplayPortInit(vcdProfile(), &osdDisplayPort) || device == OSD_DISPLAYPORT_DEVICE_MAX7456) {
if (osdDisplayPort || device == OSD_DISPLAYPORT_DEVICE_MAX7456) {
osdDisplayPortDevice = OSD_DISPLAYPORT_DEVICE_MAX7456; osdDisplayPortDevice = OSD_DISPLAYPORT_DEVICE_MAX7456;
break; break;
} }

View File

@ -335,7 +335,7 @@ void tasksInit(void)
#endif #endif
#ifdef USE_OSD #ifdef USE_OSD
setTaskEnabled(TASK_OSD, featureIsEnabled(FEATURE_OSD) && osdInitialized()); setTaskEnabled(TASK_OSD, featureIsEnabled(FEATURE_OSD) && osdGetDisplayPort(NULL));
#endif #endif
#ifdef USE_BST #ifdef USE_BST

View File

@ -115,7 +115,7 @@ static int crsfHeartbeat(displayPort_t *displayPort)
return 0; return 0;
} }
static void crsfResync(displayPort_t *displayPort) static void crsfRedraw(displayPort_t *displayPort)
{ {
displayPort->rows = crsfScreen.rows; displayPort->rows = crsfScreen.rows;
displayPort->cols = crsfScreen.cols; displayPort->cols = crsfScreen.cols;
@ -137,7 +137,7 @@ static const displayPortVTable_t crsfDisplayPortVTable = {
.writeChar = crsfWriteChar, .writeChar = crsfWriteChar,
.isTransferInProgress = crsfIsTransferInProgress, .isTransferInProgress = crsfIsTransferInProgress,
.heartbeat = crsfHeartbeat, .heartbeat = crsfHeartbeat,
.resync = crsfResync, .redraw = crsfRedraw,
.isSynced = crsfIsSynced, .isSynced = crsfIsSynced,
.txBytesFree = crsfTxBytesFree, .txBytesFree = crsfTxBytesFree,
.layerSupported = NULL, .layerSupported = NULL,
@ -174,7 +174,7 @@ void crsfDisplayPortSetDimensions(uint8_t rows, uint8_t cols)
{ {
crsfScreen.rows = MIN(rows, CRSF_DISPLAY_PORT_ROWS_MAX); crsfScreen.rows = MIN(rows, CRSF_DISPLAY_PORT_ROWS_MAX);
crsfScreen.cols = MIN(cols, CRSF_DISPLAY_PORT_COLS_MAX); crsfScreen.cols = MIN(cols, CRSF_DISPLAY_PORT_COLS_MAX);
crsfResync(&crsfDisplayPort); crsfRedraw(&crsfDisplayPort);
} }
void crsfDisplayPortRefresh(void) void crsfDisplayPortRefresh(void)

View File

@ -98,14 +98,13 @@ static void updateGridSize(displayPort_t *displayPort)
displayPort->cols = frskyOsdGetGridCols(); displayPort->cols = frskyOsdGetGridCols();
} }
static void resync(displayPort_t *displayPort) static void redraw(displayPort_t *displayPort)
{ {
UNUSED(displayPort); UNUSED(displayPort);
// TODO(agh): Do we need to flush the screen here? // TODO(agh): Do we need to flush the screen here?
// MAX7456's driver does a full redraw in resync(), // MAX7456's driver does a full redraw in redraw(),
// so some callers might be expecting that. // so some callers might be expecting that.
frskyOsdUpdate(); frskyOsdUpdate();
updateGridSize(displayPort);
} }
static int heartbeat(displayPort_t *displayPort) static int heartbeat(displayPort_t *displayPort)
@ -127,8 +126,10 @@ static bool writeFontCharacter(displayPort_t *instance, uint16_t addr, const osd
return frskyOsdWriteFontCharacter(addr, chr); return frskyOsdWriteFontCharacter(addr, chr);
} }
static bool isReady(displayPort_t *instance) static bool checkReady(displayPort_t *instance, bool rescan)
{ {
UNUSED(rescan);
if (frskyOsdIsReady()) { if (frskyOsdIsReady()) {
updateGridSize(instance); updateGridSize(instance);
return true; return true;
@ -481,10 +482,10 @@ static const displayPortVTable_t frskyOsdVTable = {
.writeChar = writeChar, .writeChar = writeChar,
.isTransferInProgress = isTransferInProgress, .isTransferInProgress = isTransferInProgress,
.heartbeat = heartbeat, .heartbeat = heartbeat,
.resync = resync, .redraw = redraw,
.txBytesFree = txBytesFree, .txBytesFree = txBytesFree,
.writeFontCharacter = writeFontCharacter, .writeFontCharacter = writeFontCharacter,
.isReady = isReady, .checkReady = checkReady,
.beginTransaction = beginTransaction, .beginTransaction = beginTransaction,
.commitTransaction = commitTransaction, .commitTransaction = commitTransaction,
.getCanvas = getCanvas, .getCanvas = getCanvas,
@ -494,7 +495,7 @@ displayPort_t *frskyOsdDisplayPortInit(const videoSystem_e videoSystem)
{ {
if (frskyOsdInit(videoSystem)) { if (frskyOsdInit(videoSystem)) {
displayInit(&frskyOsdDisplayPort, &frskyOsdVTable); displayInit(&frskyOsdDisplayPort, &frskyOsdVTable);
resync(&frskyOsdDisplayPort); redraw(&frskyOsdDisplayPort);
return &frskyOsdDisplayPort; return &frskyOsdDisplayPort;
} }
return NULL; return NULL;

View File

@ -86,7 +86,7 @@ static int hottHeartbeat(displayPort_t *displayPort)
return 0; return 0;
} }
static void hottResync(displayPort_t *displayPort) static void hottRedraw(displayPort_t *displayPort)
{ {
UNUSED(displayPort); UNUSED(displayPort);
} }
@ -121,7 +121,7 @@ static const displayPortVTable_t hottVTable = {
.writeChar = hottWriteChar, .writeChar = hottWriteChar,
.isTransferInProgress = hottIsTransferInProgress, .isTransferInProgress = hottIsTransferInProgress,
.heartbeat = hottHeartbeat, .heartbeat = hottHeartbeat,
.resync = hottResync, .redraw = hottRedraw,
.txBytesFree = hottTxBytesFree, .txBytesFree = hottTxBytesFree,
.layerSupported = NULL, .layerSupported = NULL,
.layerSelect = NULL, .layerSelect = NULL,

View File

@ -33,6 +33,8 @@
#include "config/config.h" #include "config/config.h"
#include "fc/runtime_config.h"
#include "io/displayport_max7456.h" #include "io/displayport_max7456.h"
#include "osd/osd.h" #include "osd/osd.h"
@ -41,15 +43,12 @@
#include "pg/max7456.h" #include "pg/max7456.h"
#include "pg/vcd.h" #include "pg/vcd.h"
displayPort_t max7456DisplayPort; static displayPort_t max7456DisplayPort;
static vcdProfile_t const *max7456VcdProfile;
static int grab(displayPort_t *displayPort) static int grab(displayPort_t *displayPort)
{ {
// FIXME this should probably not have a dependency on the OSD or OSD slave code
UNUSED(displayPort); UNUSED(displayPort);
#ifdef USE_OSD
resumeRefreshAt = 0;
#endif
return 0; return 0;
} }
@ -119,12 +118,13 @@ static bool isSynced(const displayPort_t *displayPort)
return max7456BuffersSynced(); return max7456BuffersSynced();
} }
static void resync(displayPort_t *displayPort) static void redraw(displayPort_t *displayPort)
{ {
UNUSED(displayPort); UNUSED(displayPort);
max7456RefreshAll();
displayPort->rows = max7456GetRowsCount() + displayPortProfileMax7456()->rowAdjust; if (!ARMING_FLAG(ARMED)) {
displayPort->cols = 30 + displayPortProfileMax7456()->colAdjust; max7456RefreshAll();
}
} }
static int heartbeat(displayPort_t *displayPort) static int heartbeat(displayPort_t *displayPort)
@ -157,25 +157,32 @@ static bool layerCopy(displayPort_t *displayPort, displayPortLayer_e destLayer,
return max7456LayerCopy(destLayer, sourceLayer); return max7456LayerCopy(destLayer, sourceLayer);
} }
static bool writeFontCharacter(displayPort_t *instance, uint16_t addr, const osdCharacter_t *chr) static bool writeFontCharacter(displayPort_t *displayPort, uint16_t addr, const osdCharacter_t *chr)
{ {
UNUSED(instance); UNUSED(displayPort);
return max7456WriteNvm(addr, (const uint8_t *)chr); return max7456WriteNvm(addr, (const uint8_t *)chr);
} }
static bool isReady(displayPort_t *instance) static bool checkReady(displayPort_t *displayPort, bool rescan)
{ {
UNUSED(instance); UNUSED(displayPort);
if (!max7456IsDeviceDetected()) { if (!max7456IsDeviceDetected()) {
// Try to initialize the device if (!rescan) {
if (max7456Init(max7456Config(), vcdProfile(), systemConfig()->cpu_overclock) != MAX7456_INIT_OK) {
return false; return false;
} else {
// Try to initialize the device
if (max7456Init(max7456Config(), max7456VcdProfile, systemConfig()->cpu_overclock) != MAX7456_INIT_OK) {
return false;
}
// At this point the device has been initialized and detected
redraw(&max7456DisplayPort);
} }
// At this point the device has been initialized and detected
resync(&max7456DisplayPort);
} }
displayPort->rows = max7456GetRowsCount() + displayPortProfileMax7456()->rowAdjust;
displayPort->cols = 30 + displayPortProfileMax7456()->colAdjust;
return true; return true;
} }
@ -189,36 +196,49 @@ static const displayPortVTable_t max7456VTable = {
.writeChar = writeChar, .writeChar = writeChar,
.isTransferInProgress = isTransferInProgress, .isTransferInProgress = isTransferInProgress,
.heartbeat = heartbeat, .heartbeat = heartbeat,
.resync = resync, .redraw = redraw,
.isSynced = isSynced, .isSynced = isSynced,
.txBytesFree = txBytesFree, .txBytesFree = txBytesFree,
.layerSupported = layerSupported, .layerSupported = layerSupported,
.layerSelect = layerSelect, .layerSelect = layerSelect,
.layerCopy = layerCopy, .layerCopy = layerCopy,
.writeFontCharacter = writeFontCharacter, .writeFontCharacter = writeFontCharacter,
.isReady = isReady, .checkReady = checkReady,
}; };
displayPort_t *max7456DisplayPortInit(const vcdProfile_t *vcdProfile) bool max7456DisplayPortInit(const vcdProfile_t *vcdProfile, displayPort_t **displayPort)
{ {
switch (max7456Init(max7456Config(), vcdProfile, systemConfig()->cpu_overclock)) { max7456VcdProfile = vcdProfile;
case MAX7456_INIT_NOT_FOUND:
// MAX7456 IO pins are defined, but we could not get a reply switch (max7456Init(max7456Config(), max7456VcdProfile, systemConfig()->cpu_overclock)) {
// from it at this time. Delay full initialization to
// isReady()
displayInit(&max7456DisplayPort, &max7456VTable);
break;
case MAX7456_INIT_OK:
// MAX7456 configured and detected
displayInit(&max7456DisplayPort, &max7456VTable);
resync(&max7456DisplayPort);
break;
case MAX7456_INIT_NOT_CONFIGURED: case MAX7456_INIT_NOT_CONFIGURED:
// MAX7456 IO pins are not defined. We either don't have // MAX7456 IO pins are not defined. We either don't have
// it on board or either the configuration for it has // it on board or either the configuration for it has
// not been set. // not been set.
return NULL; *displayPort = NULL;
return false;
break;
case MAX7456_INIT_NOT_FOUND:
// MAX7456 IO pins are defined, but we could not get a reply
// from it at this time. Delay full initialization to
// checkReady() with 'rescan' enabled
displayInit(&max7456DisplayPort, &max7456VTable);
*displayPort = &max7456DisplayPort;
return false;
break;
case MAX7456_INIT_OK:
// MAX7456 configured and detected
displayInit(&max7456DisplayPort, &max7456VTable);
redraw(&max7456DisplayPort);
*displayPort = &max7456DisplayPort;
break;
} }
return &max7456DisplayPort;
return true;
} }
#endif // USE_MAX7456 #endif // USE_MAX7456

View File

@ -25,4 +25,4 @@
#include "pg/displayport_profiles.h" #include "pg/displayport_profiles.h"
struct vcdProfile_s; struct vcdProfile_s;
displayPort_t *max7456DisplayPortInit(const struct vcdProfile_s *vcdProfile); bool max7456DisplayPortInit(const struct vcdProfile_s *vcdProfile, displayPort_t **displayPort);

View File

@ -139,7 +139,7 @@ static bool isSynced(const displayPort_t *displayPort)
return true; return true;
} }
static void resync(displayPort_t *displayPort) static void redraw(displayPort_t *displayPort)
{ {
displayPort->rows = 13 + displayPortProfileMsp()->rowAdjust; // XXX Will reflect NTSC/PAL in the future displayPort->rows = 13 + displayPortProfileMsp()->rowAdjust; // XXX Will reflect NTSC/PAL in the future
displayPort->cols = 30 + displayPortProfileMsp()->colAdjust; displayPort->cols = 30 + displayPortProfileMsp()->colAdjust;
@ -162,7 +162,7 @@ static const displayPortVTable_t mspDisplayPortVTable = {
.writeChar = writeChar, .writeChar = writeChar,
.isTransferInProgress = isTransferInProgress, .isTransferInProgress = isTransferInProgress,
.heartbeat = heartbeat, .heartbeat = heartbeat,
.resync = resync, .redraw = redraw,
.isSynced = isSynced, .isSynced = isSynced,
.txBytesFree = txBytesFree, .txBytesFree = txBytesFree,
.layerSupported = NULL, .layerSupported = NULL,
@ -178,7 +178,7 @@ displayPort_t *displayPortMspInit(void)
mspDisplayPort.useDeviceBlink = true; mspDisplayPort.useDeviceBlink = true;
} }
resync(&mspDisplayPort); redraw(&mspDisplayPort);
return &mspDisplayPort; return &mspDisplayPort;
} }
#endif // USE_MSP_DISPLAYPORT #endif // USE_MSP_DISPLAYPORT

View File

@ -95,7 +95,7 @@ static int oledHeartbeat(displayPort_t *displayPort)
return 0; return 0;
} }
static void oledResync(displayPort_t *displayPort) static void oledRedraw(displayPort_t *displayPort)
{ {
UNUSED(displayPort); UNUSED(displayPort);
} }
@ -116,7 +116,7 @@ static const displayPortVTable_t oledVTable = {
.writeChar = oledWriteChar, .writeChar = oledWriteChar,
.isTransferInProgress = oledIsTransferInProgress, .isTransferInProgress = oledIsTransferInProgress,
.heartbeat = oledHeartbeat, .heartbeat = oledHeartbeat,
.resync = oledResync, .redraw = oledRedraw,
.isSynced = oledIsSynced, .isSynced = oledIsSynced,
.txBytesFree = oledTxBytesFree, .txBytesFree = oledTxBytesFree,
.layerSupported = NULL, .layerSupported = NULL,

View File

@ -97,7 +97,7 @@ static int srxlHeartbeat(displayPort_t *displayPort)
return 0; return 0;
} }
static void srxlResync(displayPort_t *displayPort) static void srxlRedraw(displayPort_t *displayPort)
{ {
UNUSED(displayPort); UNUSED(displayPort);
} }
@ -130,7 +130,7 @@ static const displayPortVTable_t srxlVTable = {
.writeChar = srxlWriteChar, .writeChar = srxlWriteChar,
.isTransferInProgress = srxlIsTransferInProgress, .isTransferInProgress = srxlIsTransferInProgress,
.heartbeat = srxlHeartbeat, .heartbeat = srxlHeartbeat,
.resync = srxlResync, .redraw = srxlRedraw,
.isSynced = srxlIsSynced, .isSynced = srxlIsSynced,
.txBytesFree = srxlTxBytesFree, .txBytesFree = srxlTxBytesFree,
.layerSupported = NULL, .layerSupported = NULL,

View File

@ -901,17 +901,18 @@ static bool mspCommonProcessOutCommand(int16_t cmdMSP, sbuf_t *dst, mspPostProce
osdDisplayPortDevice_e deviceType; osdDisplayPortDevice_e deviceType;
displayPort_t *osdDisplayPort = osdGetDisplayPort(&deviceType); displayPort_t *osdDisplayPort = osdGetDisplayPort(&deviceType);
bool displayIsReady = osdDisplayPort && displayCheckReady(osdDisplayPort, true);
switch (deviceType) { switch (deviceType) {
case OSD_DISPLAYPORT_DEVICE_MAX7456: case OSD_DISPLAYPORT_DEVICE_MAX7456:
osdFlags |= OSD_FLAGS_OSD_HARDWARE_MAX_7456; osdFlags |= OSD_FLAGS_OSD_HARDWARE_MAX_7456;
if (osdDisplayPort && displayIsReady(osdDisplayPort)) { if (displayIsReady) {
osdFlags |= OSD_FLAGS_OSD_DEVICE_DETECTED; osdFlags |= OSD_FLAGS_OSD_DEVICE_DETECTED;
} }
break; break;
case OSD_DISPLAYPORT_DEVICE_FRSKYOSD: case OSD_DISPLAYPORT_DEVICE_FRSKYOSD:
osdFlags |= OSD_FLAGS_OSD_HARDWARE_FRSKYOSD; osdFlags |= OSD_FLAGS_OSD_HARDWARE_FRSKYOSD;
if (osdDisplayPort && displayIsReady(osdDisplayPort)) { if (displayIsReady) {
osdFlags |= OSD_FLAGS_OSD_DEVICE_DETECTED; osdFlags |= OSD_FLAGS_OSD_DEVICE_DETECTED;
} }

View File

@ -428,16 +428,11 @@ void osdInit(displayPort_t *osdDisplayPortToUse, osdDisplayPortDevice_e displayP
cmsDisplayPortRegister(osdDisplayPort); cmsDisplayPortRegister(osdDisplayPort);
#endif #endif
if (displayIsReady(osdDisplayPort)) { if (displayCheckReady(osdDisplayPort, true)) {
osdCompleteInitialization(); osdCompleteInitialization();
} }
} }
bool osdInitialized(void)
{
return osdDisplayPort;
}
static void osdResetStats(void) static void osdResetStats(void)
{ {
stats.max_current = 0; stats.max_current = 0;
@ -894,14 +889,6 @@ STATIC_UNIT_TESTED void osdRefresh(timeUs_t currentTimeUs)
static bool osdStatsVisible = false; static bool osdStatsVisible = false;
static timeUs_t osdStatsRefreshTimeUs; static timeUs_t osdStatsRefreshTimeUs;
if (!osdIsReady) {
if (!displayIsReady(osdDisplayPort)) {
displayResync(osdDisplayPort);
return;
}
osdCompleteInitialization();
}
// detect arm/disarm // detect arm/disarm
if (armState != ARMING_FLAG(ARMED)) { if (armState != ARMING_FLAG(ARMED)) {
if (ARMING_FLAG(ARMED)) { if (ARMING_FLAG(ARMED)) {
@ -1005,6 +992,14 @@ void osdUpdate(timeUs_t currentTimeUs)
{ {
static uint32_t counter = 0; static uint32_t counter = 0;
if (!osdIsReady) {
if (!displayCheckReady(osdDisplayPort, false)) {
return;
}
osdCompleteInitialization();
}
if (isBeeperOn()) { if (isBeeperOn()) {
showVisualBeeper = true; showVisualBeeper = true;
} }

View File

@ -324,19 +324,19 @@ extern escSensorData_t *osdEscDataCombined;
#endif #endif
void osdInit(displayPort_t *osdDisplayPort, osdDisplayPortDevice_e displayPortDevice); void osdInit(displayPort_t *osdDisplayPort, osdDisplayPortDevice_e displayPortDevice);
bool osdInitialized(void);
void osdUpdate(timeUs_t currentTimeUs); void osdUpdate(timeUs_t currentTimeUs);
void osdStatSetState(uint8_t statIndex, bool enabled); void osdStatSetState(uint8_t statIndex, bool enabled);
bool osdStatGetState(uint8_t statIndex); bool osdStatGetState(uint8_t statIndex);
void osdSuppressStats(bool flag);
void osdAnalyzeActiveElements(void);
void changeOsdProfileIndex(uint8_t profileIndex);
uint8_t getCurrentOsdProfileIndex(void);
displayPort_t *osdGetDisplayPort(osdDisplayPortDevice_e *displayPortDevice);
void osdWarnSetState(uint8_t warningIndex, bool enabled); void osdWarnSetState(uint8_t warningIndex, bool enabled);
bool osdWarnGetState(uint8_t warningIndex); bool osdWarnGetState(uint8_t warningIndex);
void osdSuppressStats(bool flag);
void osdAnalyzeActiveElements(void);
uint8_t getCurrentOsdProfileIndex(void);
void changeOsdProfileIndex(uint8_t profileIndex);
bool osdElementVisible(uint16_t value); bool osdElementVisible(uint16_t value);
bool osdGetVisualBeeperState(void); bool osdGetVisualBeeperState(void);
statistic_t *osdGetStats(void); statistic_t *osdGetStats(void);
bool osdNeedsAccelerometer(void); bool osdNeedsAccelerometer(void);
displayPort_t *osdGetDisplayPort(osdDisplayPortDevice_e *displayPortDevice);

View File

@ -97,7 +97,7 @@ static int displayPortTestHeartbeat(displayPort_t *displayPort)
return 0; return 0;
} }
static void displayPortTestResync(displayPort_t *displayPort) static void displayPortTestRedraw(displayPort_t *displayPort)
{ {
UNUSED(displayPort); UNUSED(displayPort);
} }
@ -118,7 +118,7 @@ static const displayPortVTable_t testDisplayPortVTable = {
.writeChar = displayPortTestWriteChar, .writeChar = displayPortTestWriteChar,
.isTransferInProgress = displayPortTestIsTransferInProgress, .isTransferInProgress = displayPortTestIsTransferInProgress,
.heartbeat = displayPortTestHeartbeat, .heartbeat = displayPortTestHeartbeat,
.resync = displayPortTestResync, .redraw = displayPortTestRedraw,
.txBytesFree = displayPortTestTxBytesFree .txBytesFree = displayPortTestTxBytesFree
}; };