diff --git a/src/main/cli/settings.c b/src/main/cli/settings.c
index 36ed629ab8..78a5749aeb 100644
--- a/src/main/cli/settings.c
+++ b/src/main/cli/settings.c
@@ -75,6 +75,7 @@
#include "pg/beeper_dev.h"
#include "pg/bus_i2c.h"
#include "pg/dashboard.h"
+#include "pg/displayport_profiles.h"
#include "pg/flash.h"
#include "pg/gyrodev.h"
#include "pg/max7456.h"
diff --git a/src/main/drivers/display.h b/src/main/drivers/display.h
index c756a97b76..8fa03f70a4 100644
--- a/src/main/drivers/display.h
+++ b/src/main/drivers/display.h
@@ -43,8 +43,6 @@ typedef struct displayPort_s {
int8_t grabCount;
} displayPort_t;
-// displayPort_t is used as a parameter group in 'displayport_msp.h' and 'displayport_max7456`.h'. Treat accordingly!
-
typedef struct displayPortVTable_s {
int (*grab)(displayPort_t *displayPort);
int (*release)(displayPort_t *displayPort);
@@ -63,17 +61,6 @@ typedef struct displayPortVTable_s {
bool (*layerCopy)(displayPort_t *displayPort, displayPortLayer_e destLayer, displayPortLayer_e sourceLayer);
} displayPortVTable_t;
-typedef struct displayPortProfile_s {
- int8_t colAdjust;
- int8_t rowAdjust;
- bool invert;
- uint8_t blackBrightness;
- uint8_t whiteBrightness;
- int8_t displayPortSerial; // serialPortIdentifier_e
-} displayPortProfile_t;
-
-// Note: displayPortProfile_t used as a parameter group for CMS over CRSF (io/displayport_crsf)
-
void displayGrab(displayPort_t *instance);
void displayRelease(displayPort_t *instance);
void displayReleaseAll(displayPort_t *instance);
diff --git a/src/main/io/displayport_max7456.c b/src/main/io/displayport_max7456.c
index 8cf0363ded..0a5531e11c 100644
--- a/src/main/io/displayport_max7456.c
+++ b/src/main/io/displayport_max7456.c
@@ -36,26 +36,12 @@
#include "osd/osd.h"
+#include "pg/displayport_profiles.h"
#include "pg/max7456.h"
-#include "pg/pg.h"
-#include "pg/pg_ids.h"
#include "pg/vcd.h"
displayPort_t max7456DisplayPort;
-PG_REGISTER_WITH_RESET_FN(displayPortProfile_t, displayPortProfileMax7456, PG_DISPLAY_PORT_MAX7456_CONFIG, 0);
-
-void pgResetFn_displayPortProfileMax7456(displayPortProfile_t *displayPortProfile)
-{
- displayPortProfile->colAdjust = 0;
- displayPortProfile->rowAdjust = 0;
-
- // Set defaults as per MAX7456 datasheet
- displayPortProfile->invert = false;
- displayPortProfile->blackBrightness = 0;
- displayPortProfile->whiteBrightness = 2;
-}
-
static int grab(displayPort_t *displayPort)
{
// FIXME this should probably not have a dependency on the OSD or OSD slave code
diff --git a/src/main/io/displayport_max7456.h b/src/main/io/displayport_max7456.h
index 9ab26ea113..9bed3d1af0 100644
--- a/src/main/io/displayport_max7456.h
+++ b/src/main/io/displayport_max7456.h
@@ -20,10 +20,9 @@
#pragma once
-#include "pg/pg.h"
#include "drivers/display.h"
-PG_DECLARE(displayPortProfile_t, displayPortProfileMax7456);
+#include "pg/displayport_profiles.h"
struct vcdProfile_s;
displayPort_t *max7456DisplayPortInit(const struct vcdProfile_s *vcdProfile);
diff --git a/src/main/io/displayport_msp.c b/src/main/io/displayport_msp.c
index 349bf56a2a..9d7ce61c54 100644
--- a/src/main/io/displayport_msp.c
+++ b/src/main/io/displayport_msp.c
@@ -29,9 +29,6 @@
#include "common/utils.h"
-#include "pg/pg.h"
-#include "pg/pg_ids.h"
-
#include "drivers/display.h"
#include "io/displayport_msp.h"
@@ -41,8 +38,6 @@
#include "msp/msp_serial.h"
// no template required since defaults are zero
-PG_REGISTER(displayPortProfile_t, displayPortProfileMsp, PG_DISPLAY_PORT_MSP_CONFIG, 0);
-
static displayPort_t mspDisplayPort;
#ifdef USE_CLI
diff --git a/src/main/io/displayport_msp.h b/src/main/io/displayport_msp.h
index d6c09309fb..cbe7283bcd 100644
--- a/src/main/io/displayport_msp.h
+++ b/src/main/io/displayport_msp.h
@@ -20,10 +20,6 @@
#pragma once
-#include "pg/pg.h"
-#include "drivers/display.h"
+#include "pg/displayport_profiles.h"
-PG_DECLARE(displayPortProfile_t, displayPortProfileMsp);
-
-struct displayPort_s;
struct displayPort_s *displayPortMspInit(void);
diff --git a/src/main/pg/displayport_profiles.c b/src/main/pg/displayport_profiles.c
new file mode 100644
index 0000000000..537c77c9e6
--- /dev/null
+++ b/src/main/pg/displayport_profiles.c
@@ -0,0 +1,50 @@
+/*
+ * This file is part of Cleanflight and Betaflight.
+ *
+ * Cleanflight and Betaflight are free software. You can redistribute
+ * this software and/or modify this software under the terms of the
+ * GNU General Public License as published by the Free Software
+ * Foundation, either version 3 of the License, or (at your option)
+ * any later version.
+ *
+ * Cleanflight and Betaflight are distributed in the hope that they
+ * will be useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ * See the GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this software.
+ *
+ * If not, see .
+ */
+
+#include
+
+#include "platform.h"
+
+#include "pg/displayport_profiles.h"
+#include "pg/pg.h"
+#include "pg/pg_ids.h"
+
+#if defined(USE_MSP_DISPLAYPORT)
+
+PG_REGISTER(displayPortProfile_t, displayPortProfileMsp, PG_DISPLAY_PORT_MSP_CONFIG, 0);
+
+#endif
+
+#if defined(USE_MAX7456)
+
+PG_REGISTER_WITH_RESET_FN(displayPortProfile_t, displayPortProfileMax7456, PG_DISPLAY_PORT_MAX7456_CONFIG, 0);
+
+void pgResetFn_displayPortProfileMax7456(displayPortProfile_t *displayPortProfile)
+{
+ displayPortProfile->colAdjust = 0;
+ displayPortProfile->rowAdjust = 0;
+
+ // Set defaults as per MAX7456 datasheet
+ displayPortProfile->invert = false;
+ displayPortProfile->blackBrightness = 0;
+ displayPortProfile->whiteBrightness = 2;
+}
+
+#endif
diff --git a/src/main/pg/displayport_profiles.h b/src/main/pg/displayport_profiles.h
new file mode 100644
index 0000000000..a4c0a62470
--- /dev/null
+++ b/src/main/pg/displayport_profiles.h
@@ -0,0 +1,36 @@
+/*
+ * This file is part of Cleanflight and Betaflight.
+ *
+ * Cleanflight and Betaflight are free software. You can redistribute
+ * this software and/or modify this software under the terms of the
+ * GNU General Public License as published by the Free Software
+ * Foundation, either version 3 of the License, or (at your option)
+ * any later version.
+ *
+ * Cleanflight and Betaflight are distributed in the hope that they
+ * will be useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ * See the GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this software.
+ *
+ * If not, see .
+ */
+
+#pragma once
+
+#include "pg/pg.h"
+
+typedef struct displayPortProfile_s {
+ int8_t colAdjust;
+ int8_t rowAdjust;
+ bool invert;
+ uint8_t blackBrightness;
+ uint8_t whiteBrightness;
+ int8_t displayPortSerial; // serialPortIdentifier_e
+} displayPortProfile_t;
+
+PG_DECLARE(displayPortProfile_t, displayPortProfileMsp);
+
+PG_DECLARE(displayPortProfile_t, displayPortProfileMax7456);