1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-25 17:25:18 +03:00

Rename HDzero to MSP displayport

This commit is contained in:
Pawel Spychalski (DzikuVx) 2022-10-01 11:22:04 +02:00
parent cdbd2b390a
commit 285a0f8180
8 changed files with 45 additions and 45 deletions

View file

@ -156,7 +156,7 @@ A shorter form is also supported to enable and disable a single function using `
| SERVO_SERIAL | 22 | 4194304 | | SERVO_SERIAL | 22 | 4194304 |
| TELEMETRY_SMARTPORT_MASTER | 23 | 8388608 | | TELEMETRY_SMARTPORT_MASTER | 23 | 8388608 |
| IMU2 | 24 | 16777216 | | IMU2 | 24 | 16777216 |
| HDZERO | 25 | 33554432 | | MSP_DISPLAYPORT | 25 | 33554432 |
Thus, to enable MSP and LTM on a port, one would use the function **value** of 17 (1 << 0)+(1<<4), aka 1+16, aka 17. Thus, to enable MSP and LTM on a port, one would use the function **value** of 17 (1 << 0)+(1<<4), aka 1+16, aka 17.

View file

@ -482,8 +482,8 @@ main_sources(COMMON_SRC
io/displayport_msp.h io/displayport_msp.h
io/displayport_oled.c io/displayport_oled.c
io/displayport_oled.h io/displayport_oled.h
io/displayport_hdzero_osd.c io/displayport_msp_osd.c
io/displayport_hdzero_osd.h io/displayport_msp_osd.h
io/displayport_srxl.c io/displayport_srxl.c
io/displayport_srxl.h io/displayport_srxl.h
io/displayport_hott.c io/displayport_hott.c

View file

@ -106,7 +106,7 @@
#include "io/displayport_frsky_osd.h" #include "io/displayport_frsky_osd.h"
#include "io/displayport_msp.h" #include "io/displayport_msp.h"
#include "io/displayport_max7456.h" #include "io/displayport_max7456.h"
#include "io/displayport_hdzero_osd.h" #include "io/displayport_msp_osd.h"
#include "io/displayport_srxl.h" #include "io/displayport_srxl.h"
#include "io/flashfs.h" #include "io/flashfs.h"
#include "io/gps.h" #include "io/gps.h"
@ -547,9 +547,9 @@ void init(void)
osdDisplayPort = frskyOSDDisplayPortInit(osdConfig()->video_system); osdDisplayPort = frskyOSDDisplayPortInit(osdConfig()->video_system);
} }
#endif #endif
#ifdef USE_HDZERO_OSD #ifdef USE_MSP_OSD
if (!osdDisplayPort) { if (!osdDisplayPort) {
osdDisplayPort = hdzeroOsdDisplayPortInit(); osdDisplayPort = mspOsdDisplayPortInit();
} }
#endif #endif
#if defined(USE_MAX7456) #if defined(USE_MAX7456)

View file

@ -66,7 +66,7 @@
#include "io/smartport_master.h" #include "io/smartport_master.h"
#include "io/vtx.h" #include "io/vtx.h"
#include "io/osd_dji_hd.h" #include "io/osd_dji_hd.h"
#include "io/displayport_hdzero_osd.h" #include "io/displayport_msp_osd.h"
#include "io/servo_sbus.h" #include "io/servo_sbus.h"
#include "msp/msp_serial.h" #include "msp/msp_serial.h"
@ -107,9 +107,9 @@ void taskHandleSerial(timeUs_t currentTimeUs)
djiOsdSerialProcess(); djiOsdSerialProcess();
#endif #endif
#ifdef USE_HDZERO_OSD #ifdef USE_MSP_OSD
// Capture HDZero messages to determine if VTX is connected // Capture MSP Displayport messages to determine if VTX is connected
hdzeroOsdSerialProcess(mspFcProcessCommand); mspOsdSerialProcess(mspFcProcessCommand);
#endif #endif
} }

View file

@ -30,9 +30,9 @@
FILE_COMPILE_FOR_SPEED FILE_COMPILE_FOR_SPEED
//#define HDZERO_STATS //#define MSP_DISPLAYPORT_STATS
#if defined(USE_OSD) && defined(USE_HDZERO_OSD) #if defined(USE_OSD) && defined(USE_MSP_OSD)
#include "common/utils.h" #include "common/utils.h"
#include "common/printf.h" #include "common/printf.h"
@ -46,7 +46,7 @@ FILE_COMPILE_FOR_SPEED
#include "msp/msp_protocol.h" #include "msp/msp_protocol.h"
#include "msp/msp_serial.h" #include "msp/msp_serial.h"
#include "displayport_hdzero_osd.h" #include "displayport_msp_osd.h"
#define FONT_VERSION 3 #define FONT_VERSION 3
@ -59,8 +59,8 @@ FILE_COMPILE_FOR_SPEED
#define VTX_TIMEOUT 1000 // 1 second timer #define VTX_TIMEOUT 1000 // 1 second timer
static mspProcessCommandFnPtr mspProcessCommand; static mspProcessCommandFnPtr mspProcessCommand;
static mspPort_t hdZeroMspPort; static mspPort_t mspPort;
static displayPort_t hdZeroOsdDisplayPort; static displayPort_t mspOsdDisplayPort;
static bool vtxSeen, vtxActive, vtxReset; static bool vtxSeen, vtxActive, vtxReset;
static timeMs_t vtxHeartbeat; static timeMs_t vtxHeartbeat;
@ -75,7 +75,7 @@ static bool screenCleared;
extern uint8_t cliMode; extern uint8_t cliMode;
#ifdef HDZERO_STATS #ifdef MSP_DISPLAYPORT_STATS
static uint32_t dataSent; static uint32_t dataSent;
static uint8_t resetCount; static uint8_t resetCount;
#endif #endif
@ -87,10 +87,10 @@ static int output(displayPort_t *displayPort, uint8_t cmd, uint8_t *subcmd, int
int sent = 0; int sent = 0;
if (!cliMode && vtxActive) { if (!cliMode && vtxActive) {
sent = mspSerialPushPort(cmd, subcmd, len, &hdZeroMspPort, MSP_V1); sent = mspSerialPushPort(cmd, subcmd, len, &mspPort, MSP_V1);
} }
#ifdef HDZERO_STATS #ifdef MSP_DISPLAYPORT_STATS
dataSent += sent; dataSent += sent;
#endif #endif
@ -111,7 +111,7 @@ static int setHdMode(displayPort_t *displayPort)
return output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd)); return output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd));
} }
static void hdZeroInit(void) static void init(void)
{ {
memset(screen, SYM_BLANK, sizeof(screen)); memset(screen, SYM_BLANK, sizeof(screen));
BITARRAY_CLR_ALL(fontPage); BITARRAY_CLR_ALL(fontPage);
@ -122,7 +122,7 @@ static int clearScreen(displayPort_t *displayPort)
{ {
uint8_t subcmd[] = { MSP_CLEAR_SCREEN }; uint8_t subcmd[] = { MSP_CLEAR_SCREEN };
hdZeroInit(); init();
setHdMode(displayPort); setHdMode(displayPort);
screenCleared = true; screenCleared = true;
return output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd)); return output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd));
@ -183,7 +183,7 @@ static int writeString(displayPort_t *displayPort, uint8_t col, uint8_t row, con
return 0; return 0;
} }
#ifdef HDZERO_STATS #ifdef MSP_DISPLAYPORT_STATS
static void printStats(displayPort_t *displayPort, uint32_t updates) static void printStats(displayPort_t *displayPort, uint32_t updates)
{ {
static timeMs_t lastTime; static timeMs_t lastTime;
@ -195,7 +195,7 @@ static void printStats(displayPort_t *displayPort, uint32_t updates)
maxUpdates = updates; // updates sent per displayWrite maxUpdates = updates; // updates sent per displayWrite
} }
uint32_t bufferUsed = TX_BUFFER_SIZE - serialTxBytesFree(hdZeroMspPort.port); uint32_t bufferUsed = TX_BUFFER_SIZE - serialTxBytesFree(mspPort.port);
if (bufferUsed > maxBufferUsed) { if (bufferUsed > maxBufferUsed) {
maxBufferUsed = bufferUsed; // serial buffer used after displayWrite maxBufferUsed = bufferUsed; // serial buffer used after displayWrite
} }
@ -212,7 +212,7 @@ static void printStats(displayPort_t *displayPort, uint32_t updates)
tfp_sprintf(lineBuffer, "R:%2d %4ld %5ld(%5ld) U:%2ld(%2ld) B:%3ld(%4ld,%4ld)", resetCount, (millis()-vtxHeartbeat), tfp_sprintf(lineBuffer, "R:%2d %4ld %5ld(%5ld) U:%2ld(%2ld) B:%3ld(%4ld,%4ld)", resetCount, (millis()-vtxHeartbeat),
dataSent, maxDataSent, updates, maxUpdates, bufferUsed, maxBufferUsed, hdZeroMspPort.port->txBufferSize); dataSent, maxDataSent, updates, maxUpdates, bufferUsed, maxBufferUsed, mspPort.port->txBufferSize);
writeString(displayPort, 0, 17, lineBuffer, 0); writeString(displayPort, 0, 17, lineBuffer, 0);
} }
#endif #endif
@ -264,13 +264,13 @@ static int drawScreen(displayPort_t *displayPort) // 250Hz
output(displayPort, MSP_DISPLAYPORT, subcmd, 1); output(displayPort, MSP_DISPLAYPORT, subcmd, 1);
} }
#ifdef HDZERO_STATS #ifdef MSP_DISPLAYPORT_STATS
printStats(displayPort, updateCount); printStats(displayPort, updateCount);
#endif #endif
checkVtxPresent(); checkVtxPresent();
if (vtxReset) { if (vtxReset) {
#ifdef HDZERO_STATS #ifdef MSP_DISPLAYPORT_STATS
resetCount++; resetCount++;
#endif #endif
clearScreen(displayPort); clearScreen(displayPort);
@ -344,7 +344,7 @@ static int release(displayPort_t *displayPort)
return 0; return 0;
} }
static const displayPortVTable_t hdzeroOsdVTable = { static const displayPortVTable_t mspOsdVTable = {
.grab = grab, .grab = grab,
.release = release, .release = release,
.clearScreen = clearScreen, .clearScreen = clearScreen,
@ -362,14 +362,14 @@ static const displayPortVTable_t hdzeroOsdVTable = {
.isReady = isReady, .isReady = isReady,
}; };
bool hdzeroOsdSerialInit(void) bool mspOsdSerialInit(void)
{ {
static volatile uint8_t txBuffer[TX_BUFFER_SIZE]; static volatile uint8_t txBuffer[TX_BUFFER_SIZE];
memset(&hdZeroMspPort, 0, sizeof(mspPort_t)); memset(&mspPort, 0, sizeof(mspPort_t));
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_HDZERO_OSD); serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP_OSD);
if (portConfig) { if (portConfig) {
serialPort_t *port = openSerialPort(portConfig->identifier, FUNCTION_HDZERO_OSD, NULL, NULL, serialPort_t *port = openSerialPort(portConfig->identifier, FUNCTION_MSP_OSD, NULL, NULL,
baudRates[portConfig->peripheral_baudrateIndex], MODE_RXTX, SERIAL_NOT_INVERTED); baudRates[portConfig->peripheral_baudrateIndex], MODE_RXTX, SERIAL_NOT_INVERTED);
if (port) { if (port) {
@ -379,7 +379,7 @@ bool hdzeroOsdSerialInit(void)
port->txBufferTail = 0; port->txBufferTail = 0;
port->txBufferHead = 0; port->txBufferHead = 0;
resetMspPort(&hdZeroMspPort, port); resetMspPort(&mspPort, port);
return true; return true;
} }
@ -388,12 +388,12 @@ bool hdzeroOsdSerialInit(void)
return false; return false;
} }
displayPort_t* hdzeroOsdDisplayPortInit(void) displayPort_t* mspOsdDisplayPortInit(void)
{ {
if (hdzeroOsdSerialInit()) { if (mspOsdSerialInit()) {
hdZeroInit(); init();
displayInit(&hdZeroOsdDisplayPort, &hdzeroOsdVTable); displayInit(&osdDisplayPort, &mspOsdVTable);
return &hdZeroOsdDisplayPort; return &osdDisplayPort;
} }
return NULL; return NULL;
} }
@ -403,7 +403,7 @@ displayPort_t* hdzeroOsdDisplayPortInit(void)
* VTX sends an MSP command every 125ms or so. * VTX sends an MSP command every 125ms or so.
* VTX will have be marked as not ready if no commands received within VTX_TIMEOUT. * VTX will have be marked as not ready if no commands received within VTX_TIMEOUT.
*/ */
static mspResult_e hdZeroProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn) static mspResult_e processMspCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn)
{ {
if (vtxSeen && !vtxActive) { if (vtxSeen && !vtxActive) {
vtxReset = true; vtxReset = true;
@ -416,12 +416,12 @@ static mspResult_e hdZeroProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply,
return mspProcessCommand(cmd, reply, mspPostProcessFn); return mspProcessCommand(cmd, reply, mspPostProcessFn);
} }
void hdzeroOsdSerialProcess(mspProcessCommandFnPtr mspProcessCommandFn) void mspOsdSerialProcess(mspProcessCommandFnPtr mspProcessCommandFn)
{ {
if (hdZeroMspPort.port) { if (mspPort.port) {
mspProcessCommand = mspProcessCommandFn; mspProcessCommand = mspProcessCommandFn;
mspSerialProcessOnePort(&hdZeroMspPort, MSP_SKIP_NON_MSP_DATA, hdZeroProcessMspCommand); mspSerialProcessOnePort(&mspPort, MSP_SKIP_NON_MSP_DATA, processMspCommand);
} }
} }
#endif // USE_HDZERO_OSD #endif // USE_MSP_OSD

View file

@ -29,5 +29,5 @@
typedef struct displayPort_s displayPort_t; typedef struct displayPort_s displayPort_t;
displayPort_t *hdzeroOsdDisplayPortInit(void); displayPort_t *mspOsdDisplayPortInit(void);
void hdzeroOsdSerialProcess(mspProcessCommandFnPtr mspProcessCommandFn); void mspOsdSerialProcess(mspProcessCommandFnPtr mspProcessCommandFn);

View file

@ -56,7 +56,7 @@ typedef enum {
FUNCTION_SERVO_SERIAL = (1 << 22), // 4194304 FUNCTION_SERVO_SERIAL = (1 << 22), // 4194304
FUNCTION_TELEMETRY_SMARTPORT_MASTER = (1 << 23), // 8388608 FUNCTION_TELEMETRY_SMARTPORT_MASTER = (1 << 23), // 8388608
FUNCTION_IMU2 = (1 << 24), // 16777216 FUNCTION_IMU2 = (1 << 24), // 16777216
FUNCTION_HDZERO_OSD = (1 << 25), // 33554432 FUNCTION_MSP_OSD = (1 << 25), // 33554432
} serialPortFunction_e; } serialPortFunction_e;
typedef enum { typedef enum {

View file

@ -114,7 +114,7 @@
#define USE_OSD #define USE_OSD
#define USE_FRSKYOSD #define USE_FRSKYOSD
#define USE_DJI_HD_OSD #define USE_DJI_HD_OSD
#define USE_HDZERO_OSD #define USE_MSP_OSD
#define USE_SMARTPORT_MASTER #define USE_SMARTPORT_MASTER
#define NAV_NON_VOLATILE_WAYPOINT_CLI #define NAV_NON_VOLATILE_WAYPOINT_CLI