1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 00:35:39 +03:00

Merge pull request #11913 from SteveCEvans/msp_dp

Enable MSP Displayport on a serial port using FUNCTION_MSP_DISPLAYPORT
This commit is contained in:
haslinghuis 2022-10-25 12:52:34 +02:00 committed by GitHub
commit b8bacc47f3
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
9 changed files with 61 additions and 55 deletions

View file

@ -1509,7 +1509,6 @@ const clivalue_t valueTable[] = {
#ifdef USE_MSP_DISPLAYPORT
{ "displayport_msp_col_adjust", VAR_INT8 | MASTER_VALUE, .config.minmax = { -6, 0 }, PG_DISPLAY_PORT_MSP_CONFIG, offsetof(displayPortProfile_t, colAdjust) },
{ "displayport_msp_row_adjust", VAR_INT8 | MASTER_VALUE, .config.minmax = { -3, 0 }, PG_DISPLAY_PORT_MSP_CONFIG, offsetof(displayPortProfile_t, rowAdjust) },
{ "displayport_msp_serial", VAR_INT8 | MASTER_VALUE, .config.minmax = { SERIAL_PORT_NONE, SERIAL_PORT_IDENTIFIER_MAX }, PG_DISPLAY_PORT_MSP_CONFIG, offsetof(displayPortProfile_t, displayPortSerial) },
{ "displayport_msp_attrs", VAR_UINT8 | MASTER_VALUE | MODE_ARRAY, .config.array.length = 4, PG_DISPLAY_PORT_MSP_CONFIG, offsetof(displayPortProfile_t, attrValues) },
{ "displayport_msp_use_device_blink", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_DISPLAY_PORT_MSP_CONFIG, offsetof(displayPortProfile_t, useDeviceBlink) },
#endif

View file

@ -57,6 +57,7 @@
#include "flight/position.h"
#include "io/beeper.h"
#include "io/displayport_msp.h"
#include "io/gps.h"
#include "io/ledstrip.h"
#include "io/serial.h"
@ -577,15 +578,17 @@ static void validateAndFixConfig(void)
}
#ifdef USE_MSP_DISPLAYPORT
// validate that displayport_msp_serial is referencing a valid UART that actually has MSP enabled
if (displayPortProfileMsp()->displayPortSerial != SERIAL_PORT_NONE) {
const serialPortConfig_t *portConfig = serialFindPortConfiguration(displayPortProfileMsp()->displayPortSerial);
if (!portConfig || !(portConfig->functionMask & FUNCTION_MSP)
#ifndef USE_MSP_PUSH_OVER_VCP
|| (portConfig->identifier == SERIAL_PORT_USB_VCP)
#endif
) {
displayPortProfileMspMutable()->displayPortSerial = SERIAL_PORT_NONE;
// Find the first serial port on which MSP Displayport is enabled
displayPortMspSetSerial(SERIAL_PORT_NONE);
for (uint8_t serialPort = 0; serialPort < SERIAL_PORT_COUNT; serialPort++) {
const serialPortConfig_t *portConfig = &serialConfig()->portConfigs[serialPort];
if (portConfig &&
(portConfig->identifier != SERIAL_PORT_USB_VCP) &&
((portConfig->functionMask & FUNCTION_MSP_DISPLAYPORT) == FUNCTION_MSP_DISPLAYPORT)) {
displayPortMspSetSerial(portConfig->identifier);
break;
}
}
#endif

View file

@ -43,6 +43,7 @@
#include "pg/vcd.h"
static displayPort_t mspDisplayPort;
static serialPortIdentifier_e displayPortSerial;
static int output(displayPort_t *displayPort, uint8_t cmd, uint8_t *buf, int len)
{
@ -54,7 +55,7 @@ static int output(displayPort_t *displayPort, uint8_t cmd, uint8_t *buf, int len
return 0;
}
#endif
return mspSerialPush(displayPortProfileMsp()->displayPortSerial, cmd, buf, len, MSP_DIRECTION_REPLY, MSP_V1);
return mspSerialPush(displayPortSerial, cmd, buf, len, MSP_DIRECTION_REPLY, MSP_V1);
}
static int heartbeat(displayPort_t *displayPort)
@ -191,4 +192,8 @@ displayPort_t *displayPortMspInit(void)
redraw(&mspDisplayPort);
return &mspDisplayPort;
}
void displayPortMspSetSerial(serialPortIdentifier_e serialPort) {
displayPortSerial = serialPort;
}
#endif // USE_MSP_DISPLAYPORT

View file

@ -22,6 +22,8 @@
#include "drivers/display.h"
#include "io/serial.h"
#include "pg/displayport_profiles.h"
// MSP Display Port commands
@ -36,3 +38,5 @@
#define DISPLAYPORT_MSP_ATTR_MASK (~(DISPLAYPORT_MSP_ATTR_VERSION|DISPLAYPORT_MSP_ATTR_BLINK))
struct displayPort_s *displayPortMspInit(void);
void displayPortMspSetSerial(serialPortIdentifier_e serialPort);

View file

@ -272,9 +272,9 @@ serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e s
}
#ifdef USE_TELEMETRY
#define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | TELEMETRY_PORT_FUNCTIONS_MASK | FUNCTION_VTX_MSP)
#define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | TELEMETRY_PORT_FUNCTIONS_MASK | FUNCTION_VTX_MSP | FUNCTION_MSP_DISPLAYPORT)
#else
#define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | FUNCTION_VTX_MSP)
#define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | FUNCTION_VTX_MSP | FUNCTION_MSP_DISPLAYPORT)
#endif
bool isSerialConfigValid(const serialConfig_t *serialConfigToCheck)

View file

@ -51,6 +51,7 @@ typedef enum {
FUNCTION_LIDAR_TF = (1 << 15), // 32768
FUNCTION_FRSKY_OSD = (1 << 16), // 65536
FUNCTION_VTX_MSP = (1 << 17), // 131072
FUNCTION_MSP_DISPLAYPORT = (1 << 18) | FUNCTION_MSP, // 262145
} serialPortFunction_e;
#define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY_HUB | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK)

View file

@ -30,12 +30,7 @@
#if defined(USE_MSP_DISPLAYPORT)
PG_REGISTER_WITH_RESET_FN(displayPortProfile_t, displayPortProfileMsp, PG_DISPLAY_PORT_MSP_CONFIG, 0);
void pgResetFn_displayPortProfileMsp(displayPortProfile_t *displayPortProfile)
{
displayPortProfile->displayPortSerial = SERIAL_PORT_NONE;
}
PG_REGISTER(displayPortProfile_t, displayPortProfileMsp, PG_DISPLAY_PORT_MSP_CONFIG, 1);
#endif

View file

@ -28,7 +28,6 @@ typedef struct displayPortProfile_s {
bool invert;
uint8_t blackBrightness;
uint8_t whiteBrightness;
int8_t displayPortSerial; // serialPortIdentifier_e
// For attribute-rich OSDs