Cleaned up parameter group definitions for displayPort.

This commit is contained in:
mikeller 2019-10-27 22:14:06 +13:00
parent 887a913c6e
commit d71b117c3e
8 changed files with 90 additions and 40 deletions

View File

@ -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"

View File

@ -37,8 +37,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);
@ -54,17 +52,6 @@ typedef struct displayPortVTable_s {
uint32_t (*txBytesFree)(const displayPort_t *displayPort);
} 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);

View File

@ -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

View File

@ -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);

View File

@ -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

View File

@ -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);

View File

@ -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 <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#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

View File

@ -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 <http://www.gnu.org/licenses/>.
*/
#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);