Merge pull request #5 from martinbudden/jf_osd4

CMS file renaming. displayPort renaming
This commit is contained in:
jflyper 2016-11-07 05:52:24 +09:00 committed by GitHub
commit ca4601bc46
37 changed files with 248 additions and 250 deletions

View File

@ -551,6 +551,12 @@ COMMON_SRC = \
HIGHEND_SRC = \
blackbox/blackbox.c \
blackbox/blackbox_io.c \
cms/cms.c \
cms/cms_menu_blackbox.c \
cms/cms_menu_builtin.c \
cms/cms_menu_imu.c \
cms/cms_menu_ledstrip.c \
cms/cms_menu_vtx.c \
common/colorconversion.c \
drivers/display_ug2864hsweg01.c \
drivers/light_ws2811strip.c \
@ -560,19 +566,13 @@ HIGHEND_SRC = \
flight/gtune.c \
flight/navigation.c \
flight/gps_conversion.c \
io/canvas.c \
io/cms.c \
io/cms_builtin.c \
io/cms_imu.c \
io/cms_blackbox.c \
io/cms_vtx.c \
io/cms_ledstrip.c \
io/displayport_oled.c \
io/dashboard.c \
io/displayport_max7456.c \
io/displayport_msp.c \
io/displayport_oled.c \
io/gps.c \
io/ledstrip.c \
io/osd.c \
io/osd_max7456.c \
sensors/sonar.c \
sensors/barometer.c \
telemetry/telemetry.c \

View File

@ -30,16 +30,19 @@
#include "platform.h"
#include "build/version.h"
#ifdef CMS
#include "build/version.h"
#include "build/debug.h"
#include "drivers/system.h"
#include "cms/cms.h"
#include "cms/cms_menu_builtin.h"
#include "cms/cms_types.h"
#include "common/typeconversion.h"
#include "drivers/system.h"
// For 'ARM' related
#include "fc/config.h"
#include "fc/rc_controls.h"
@ -53,12 +56,6 @@
// For VISIBLE* (Actually, included by config_master.h)
#include "io/osd.h"
#include "io/cms.h"
#include "io/cms_types.h"
// Menu contents
#include "io/cms_builtin.h"
// DisplayPort management
#ifndef CMS_MAX_DEVICE
@ -528,13 +525,13 @@ static void cmsMenuOpen(void)
// Switch display
displayPort_t *pNextDisplay = cmsDisplayPortSelectNext();
if (pNextDisplay != pCurrentDisplay) {
displayClose(pCurrentDisplay);
displayRelease(pCurrentDisplay);
pCurrentDisplay = pNextDisplay;
} else {
return;
}
}
displayOpen(pCurrentDisplay);
displayGrab(pCurrentDisplay); // grab the display for use by the CMS
cmsMenuChange(pCurrentDisplay, currentMenu);
}
@ -578,7 +575,7 @@ long cmsMenuExit(displayPort_t *pDisplay, void *ptr)
cmsInMenu = false;
displayClose(pDisplay);
displayRelease(pDisplay);
currentMenu = NULL;
if (ptr)

View File

@ -32,14 +32,14 @@
#include "drivers/system.h"
#include "cms/cms.h"
#include "cms/cms_types.h"
#include "cms/cms_menu_blackbox.h"
#include "config/config_profile.h"
#include "config/config_master.h"
#include "config/feature.h"
#include "io/cms.h"
#include "io/cms_types.h"
#include "io/cms_blackbox.h"
#include "io/flashfs.h"
#ifdef USE_FLASHFS

View File

@ -26,25 +26,23 @@
#include "platform.h"
#include "build/version.h"
#ifdef CMS
#include "build/version.h"
#include "drivers/system.h"
#include "io/cms.h"
#include "io/cms_types.h"
#include "io/cms_imu.h"
#include "cms/cms.h"
#include "cms/cms_types.h"
#include "cms/cms_menu_builtin.h"
// Sub menus
#include "io/cms_imu.h"
#include "io/cms_blackbox.h"
#include "io/cms_vtx.h"
#ifdef OSD
#include "io/cms_osd.h"
#endif
#include "io/cms_ledstrip.h"
#include "cms/cms_menu_imu.h"
#include "cms/cms_menu_blackbox.h"
#include "cms/cms_menu_vtx.h"
#include "cms/cms_menu_osd.h"
#include "cms/cms_menu_ledstrip.h"
// Info

View File

@ -17,4 +17,6 @@
#pragma once
#include "cms/cms_types.h"
extern CMS_Menu menuMain;

View File

@ -25,17 +25,17 @@
#include "platform.h"
#include "build/version.h"
#ifdef CMS
#include "build/version.h"
#include "drivers/system.h"
//#include "common/typeconversion.h"
#include "io/cms.h"
#include "io/cms_types.h"
#include "io/cms_imu.h"
#include "cms/cms.h"
#include "cms/cms_types.h"
#include "cms/cms_menu_imu.h"
#include "fc/config.h"
#include "fc/rc_controls.h"

View File

@ -32,9 +32,9 @@
#include "config/config_master.h"
#include "config/feature.h"
#include "io/cms.h"
#include "io/cms_types.h"
#include "io/cms_blackbox.h"
#include "cms/cms.h"
#include "cms/cms_types.h"
#include "cms/cms_menu_ledstrip.h"
#ifdef LED_STRIP

View File

@ -23,9 +23,9 @@
#include "build/version.h"
#include "io/cms.h"
#include "io/cms_types.h"
#include "io/cms_vtx.h"
#include "cms/cms.h"
#include "cms/cms_types.h"
#include "cms/cms_menu_vtx.h"
#include "config/config_profile.h"
#include "config/config_master.h"

View File

@ -21,6 +21,8 @@
#include "config/config_profile.h"
#include "cms/cms.h"
#include "drivers/pwm_rx.h"
#include "drivers/sound_beeper.h"
#include "drivers/sonar_hcsr04.h"
@ -38,7 +40,6 @@
#include "io/motors.h"
#include "io/servos.h"
#include "io/gps.h"
#include "io/cms.h"
#include "io/osd.h"
#include "io/ledstrip.h"
#include "io/vtx.h"

View File

@ -31,22 +31,22 @@ void displayClear(displayPort_t *instance)
instance->cursorRow = -1;
}
void displayOpen(displayPort_t *instance)
void displayGrab(displayPort_t *instance)
{
instance->vTable->open(instance);
instance->vTable->grab(instance);
instance->vTable->clear(instance);
instance->isOpen = true;
instance->isGrabbed = true;
}
void displayClose(displayPort_t *instance)
void displayRelease(displayPort_t *instance)
{
instance->vTable->close(instance);
instance->isOpen = false;
instance->vTable->release(instance);
instance->isGrabbed = false;
}
bool displayIsOpen(const displayPort_t *instance)
bool displayIsGrabbed(const displayPort_t *instance)
{
if (instance && instance->isOpen) { // can be called before initialised
if (instance && instance->isGrabbed) { // can be called before initialised
return true;
} else {
return false;

View File

@ -26,12 +26,12 @@ typedef struct displayPort_s {
// CMS state
bool cleared;
int8_t cursorRow;
bool isOpen;
bool isGrabbed;
} displayPort_t;
typedef struct displayPortVTable_s {
int (*open)(displayPort_t *displayPort);
int (*close)(displayPort_t *displayPort);
int (*grab)(displayPort_t *displayPort);
int (*release)(displayPort_t *displayPort);
int (*clear)(displayPort_t *displayPort);
int (*write)(displayPort_t *displayPort, uint8_t x, uint8_t y, const char *text);
int (*heartbeat)(displayPort_t *displayPort);
@ -39,9 +39,9 @@ typedef struct displayPortVTable_s {
uint32_t (*txBytesFree)(const displayPort_t *displayPort);
} displayPortVTable_t;
void displayOpen(displayPort_t *instance);
void displayClose(displayPort_t *instance);
bool displayIsOpen(const displayPort_t *instance);
void displayGrab(displayPort_t *instance);
void displayRelease(displayPort_t *instance);
bool displayIsGrabbed(const displayPort_t *instance);
void displayClear(displayPort_t *instance);
int displayWrite(displayPort_t *instance, uint8_t x, uint8_t y, const char *s);
void displayHeartbeat(displayPort_t *instance);

View File

@ -26,6 +26,8 @@
#include "blackbox/blackbox_io.h"
#include "cms/cms.h"
#include "common/color.h"
#include "common/axis.h"
#include "common/maths.h"
@ -64,7 +66,6 @@
#include "io/servos.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/cms.h"
#include "io/osd.h"
#include "io/vtx.h"

View File

@ -55,7 +55,7 @@ typedef enum {
FEATURE_VTX = 1 << 24,
FEATURE_RX_SPI = 1 << 25,
FEATURE_SOFTSPI = 1 << 26,
FEATURE_CANVAS = 1 << 27,
FEATURE_MSP_OSD = 1 << 27,
} features_e;
void beeperOffSet(uint32_t mask);

View File

@ -21,6 +21,8 @@
#include <platform.h>
#include "cms/cms.h"
#include "common/axis.h"
#include "common/color.h"
#include "common/utils.h"
@ -41,7 +43,6 @@
#include "flight/altitudehold.h"
#include "io/beeper.h"
#include "io/cms.h"
#include "io/dashboard.h"
#include "io/gps.h"
#include "io/ledstrip.h"

View File

@ -1,122 +0,0 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it 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 is distributed in the hope that it 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <ctype.h>
#include "platform.h"
#ifdef CANVAS
#include "build/version.h"
#include "common/utils.h"
#include "drivers/system.h"
#include "io/cms.h"
#include "fc/fc_msp.h"
#include "msp/msp_protocol.h"
#include "msp/msp_serial.h"
static displayPort_t canvasDisplayPort;
static int canvasOutput(displayPort_t *displayPort, uint8_t cmd, const uint8_t *buf, int len)
{
UNUSED(displayPort);
return mspSerialPush(cmd, buf, len);
}
static int canvasOpen(displayPort_t *displayPort)
{
const uint8_t subcmd[] = { 0 };
return canvasOutput(displayPort, MSP_CANVAS, subcmd, sizeof(subcmd));
}
static int canvasHeartBeat(displayPort_t *displayPort)
{
return canvasOpen(displayPort);
}
static int canvasClose(displayPort_t *displayPort)
{
const uint8_t subcmd[] = { 1 };
return canvasOutput(displayPort, MSP_CANVAS, subcmd, sizeof(subcmd));
}
static int canvasClear(displayPort_t *displayPort)
{
const uint8_t subcmd[] = { 2 };
return canvasOutput(displayPort, MSP_CANVAS, subcmd, sizeof(subcmd));
}
static int canvasWrite(displayPort_t *displayPort, uint8_t col, uint8_t row, const char *string)
{
#define MSP_CANVAS_MAX_STRING_LENGTH 30
uint8_t buf[MSP_CANVAS_MAX_STRING_LENGTH + 4];
int len = strlen(string);
if (len >= MSP_CANVAS_MAX_STRING_LENGTH) {
len = MSP_CANVAS_MAX_STRING_LENGTH;
}
buf[0] = 3;
buf[1] = row;
buf[2] = col;
buf[3] = 0;
memcpy(&buf[4], string, len);
return canvasOutput(displayPort, MSP_CANVAS, buf, len + 4);
}
static void canvasResync(displayPort_t *displayPort)
{
displayPort->rows = 13; // XXX Will reflect NTSC/PAL in the future
displayPort->cols = 30;
}
static uint32_t canvasTxBytesFree(const displayPort_t *displayPort)
{
UNUSED(displayPort);
return mspSerialTxBytesFree();
}
static const displayPortVTable_t canvasVTable = {
.open = canvasOpen,
.close = canvasClose,
.clear = canvasClear,
.write = canvasWrite,
.heartbeat = canvasHeartBeat,
.resync = canvasResync,
.txBytesFree = canvasTxBytesFree
};
displayPort_t *canvasInit(void)
{
canvasDisplayPort.vTable = &canvasVTable;
canvasDisplayPort.isOpen = false;
canvasResync(&canvasDisplayPort);
return &canvasDisplayPort;
}
#endif

View File

@ -34,6 +34,8 @@
#include "drivers/display.h"
#include "drivers/display_ug2864hsweg01.h"
#include "cms/cms.h"
#include "common/printf.h"
#include "common/maths.h"
#include "common/axis.h"
@ -53,7 +55,6 @@
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "io/cms.h"
#include "io/displayport_oled.h"
#ifdef GPS
@ -589,7 +590,7 @@ void dashboardUpdate(uint32_t currentTime)
static uint8_t previousArmedState = 0;
#ifdef OLEDCMS
if (displayIsOpen(displayPort)) {
if (displayIsGrabbed(displayPort)) {
return;
}
#endif

View File

@ -29,29 +29,29 @@
#include "drivers/display.h"
#include "drivers/max7456.h"
displayPort_t osd7456DisplayPort; // Referenced from osd.c
displayPort_t max7456DisplayPort; // Referenced from osd.c
extern uint16_t refreshTimeout;
static int osdMenuOpen(displayPort_t *displayPort)
static int grab(displayPort_t *displayPort)
{
UNUSED(displayPort);
osdResetAlarms();
displayPort->isOpen = true;
displayPort->isGrabbed = true;
refreshTimeout = 0;
return 0;
}
static int osdMenuClose(displayPort_t *displayPort)
static int release(displayPort_t *displayPort)
{
UNUSED(displayPort);
displayPort->isOpen = false;
displayPort->isGrabbed = false;
return 0;
}
static int osdClearScreen(displayPort_t *displayPort)
static int clearScreen(displayPort_t *displayPort)
{
UNUSED(displayPort);
max7456ClearScreen();
@ -59,7 +59,7 @@ static int osdClearScreen(displayPort_t *displayPort)
return 0;
}
static int osdWrite(displayPort_t *displayPort, uint8_t x, uint8_t y, const char *s)
static int write(displayPort_t *displayPort, uint8_t x, uint8_t y, const char *s)
{
UNUSED(displayPort);
max7456Write(x, y, s);
@ -67,7 +67,7 @@ static int osdWrite(displayPort_t *displayPort, uint8_t x, uint8_t y, const char
return 0;
}
static void osdResync(displayPort_t *displayPort)
static void resync(displayPort_t *displayPort)
{
UNUSED(displayPort);
max7456RefreshAll();
@ -75,33 +75,33 @@ static void osdResync(displayPort_t *displayPort)
displayPort->cols = 30;
}
static int osdHeartbeat(displayPort_t *displayPort)
static int heartbeat(displayPort_t *displayPort)
{
UNUSED(displayPort);
return 0;
}
static uint32_t osdTxBytesFree(const displayPort_t *displayPort)
static uint32_t txBytesFree(const displayPort_t *displayPort)
{
UNUSED(displayPort);
return UINT32_MAX;
}
static displayPortVTable_t osdVTable = {
.open = osdMenuOpen,
.close = osdMenuClose,
.clear = osdClearScreen,
.write = osdWrite,
.heartbeat = osdHeartbeat,
.resync = osdResync,
.txBytesFree = osdTxBytesFree,
static displayPortVTable_t max7456VTable = {
.grab = grab,
.release = release,
.clear = clearScreen,
.write = write,
.heartbeat = heartbeat,
.resync = resync,
.txBytesFree = txBytesFree,
};
displayPort_t *osd7456DisplayPortInit(void)
displayPort_t *max7456DisplayPortInit(void)
{
osd7456DisplayPort.vTable = &osdVTable;
osd7456DisplayPort.isOpen = false;
osdResync(&osd7456DisplayPort);
return &osd7456DisplayPort;
max7456DisplayPort.vTable = &max7456VTable;
max7456DisplayPort.isGrabbed = false;
resync(&max7456DisplayPort);
return &max7456DisplayPort;
}
#endif // OSD

View File

@ -17,4 +17,4 @@
#pragma once
displayPort_t *osd7456DisplayPortInit(void);
displayPort_t *max7456DisplayPortInit(void);

View File

@ -0,0 +1,119 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it 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 is distributed in the hope that it 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <ctype.h>
#include "platform.h"
#ifdef USE_MSP_DISPLAYPORT
#include "common/utils.h"
#include "drivers/display.h"
#include "drivers/system.h"
#include "fc/fc_msp.h"
#include "msp/msp_protocol.h"
#include "msp/msp_serial.h"
static displayPort_t mspDisplayPort;
static int output(displayPort_t *displayPort, uint8_t cmd, const uint8_t *buf, int len)
{
UNUSED(displayPort);
return mspSerialPush(cmd, buf, len);
}
static int grab(displayPort_t *displayPort)
{
const uint8_t subcmd[] = { 0 };
return output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd));
}
static int heartbeat(displayPort_t *displayPort)
{
return grab(displayPort); // ensure display is not released by MW OSD software
}
static int release(displayPort_t *displayPort)
{
const uint8_t subcmd[] = { 1 };
return output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd));
}
static int clear(displayPort_t *displayPort)
{
const uint8_t subcmd[] = { 2 };
return output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd));
}
static int write(displayPort_t *displayPort, uint8_t col, uint8_t row, const char *string)
{
#define MSP_OSD_MAX_STRING_LENGTH 30
uint8_t buf[MSP_OSD_MAX_STRING_LENGTH + 4];
int len = strlen(string);
if (len >= MSP_OSD_MAX_STRING_LENGTH) {
len = MSP_OSD_MAX_STRING_LENGTH;
}
buf[0] = 3;
buf[1] = row;
buf[2] = col;
buf[3] = 0;
memcpy(&buf[4], string, len);
return output(displayPort, MSP_DISPLAYPORT, buf, len + 4);
}
static void resync(displayPort_t *displayPort)
{
displayPort->rows = 13; // XXX Will reflect NTSC/PAL in the future
displayPort->cols = 30;
}
static uint32_t txBytesFree(const displayPort_t *displayPort)
{
UNUSED(displayPort);
return mspSerialTxBytesFree();
}
static const displayPortVTable_t mspDisplayPortVTable = {
.grab = grab,
.release = release,
.clear = clear,
.write = write,
.heartbeat = heartbeat,
.resync = resync,
.txBytesFree = txBytesFree
};
displayPort_t *displayPortMspInit(void)
{
mspDisplayPort.vTable = &mspDisplayPortVTable;
mspDisplayPort.isGrabbed = false;
resync(&mspDisplayPort);
return &mspDisplayPort;
}
#endif // USE_MSP_DISPLAYPORT

View File

@ -18,4 +18,4 @@
#pragma once
struct displayPort_s;
struct displayPort_s *canvasInit(void);
struct displayPort_s *displayPortMspInit(void);

View File

@ -27,13 +27,13 @@
static displayPort_t oledDisplayPort;
static int oledOpen(displayPort_t *displayPort)
static int oledGrab(displayPort_t *displayPort)
{
UNUSED(displayPort);
return 0;
}
static int oledClose(displayPort_t *displayPort)
static int oledRelease(displayPort_t *displayPort)
{
UNUSED(displayPort);
return 0;
@ -72,8 +72,8 @@ static uint32_t oledTxBytesFree(const displayPort_t *displayPort)
}
static const displayPortVTable_t oledVTable = {
.open = oledOpen,
.close = oledClose,
.grab = oledGrab,
.release = oledRelease,
.clear = oledClear,
.write = oledWrite,
.heartbeat = oledHeartbeat,
@ -86,6 +86,6 @@ displayPort_t *displayPortOledInit(void)
oledDisplayPort.vTable = &oledVTable;
oledDisplayPort.rows = SCREEN_CHARACTER_ROW_COUNT;
oledDisplayPort.cols = SCREEN_CHARACTER_COLUMN_COUNT;
oledDisplayPort.isOpen = false;
oledDisplayPort.isGrabbed = false;
return &oledDisplayPort;
}

View File

@ -35,14 +35,16 @@
#include "common/utils.h"
#include "drivers/display.h"
#include "drivers/system.h"
#include "io/cms.h"
#include "io/cms_types.h"
#include "io/cms_osd.h"
#include "cms/cms.h"
#include "cms/cms_types.h"
#include "cms/cms_menu_osd.h"
#include "io/displayport_max7456.h"
#include "io/flashfs.h"
#include "io/osd.h"
#include "io/osd_max7456.h"
#include "fc/config.h"
#include "fc/rc_controls.h"
@ -119,7 +121,7 @@ void osdDrawElements(void)
;
#endif
#ifdef CMS
else if (sensors(SENSOR_ACC) || displayIsOpen(osd7456DisplayPort))
else if (sensors(SENSOR_ACC) || displayIsGrabbed(osd7456DisplayPort))
#else
else if (sensors(SENSOR_ACC))
#endif
@ -142,7 +144,7 @@ void osdDrawElements(void)
#ifdef GPS
#ifdef CMS
if (sensors(SENSOR_GPS) || displayIsOpen(osd7456DisplayPort))
if (sensors(SENSOR_GPS) || displayIsGrabbed(osd7456DisplayPort))
#else
if (sensors(SENSOR_GPS))
#endif
@ -416,7 +418,7 @@ void osdInit(void)
refreshTimeout = 4 * REFRESH_1S;
osd7456DisplayPort = osd7456DisplayPortInit();
osd7456DisplayPort = max7456DisplayPortInit();
#ifdef CMS
cmsDisplayPortRegister(osd7456DisplayPort);
#endif
@ -595,7 +597,7 @@ void updateOsd(uint32_t currentTime)
#ifdef CMS
// do not allow ARM if we are in menu
if (displayIsOpen(osd7456DisplayPort)) {
if (displayIsGrabbed(osd7456DisplayPort)) {
DISABLE_ARMING_FLAG(OK_TO_ARM);
}
#endif
@ -644,7 +646,7 @@ void osdUpdate(uint32_t currentTime)
blinkState = (millis() / 200) % 2;
#ifdef CMS
if (!displayIsOpen(osd7456DisplayPort)) {
if (!displayIsGrabbed(osd7456DisplayPort)) {
osdUpdateAlarms();
osdDrawElements();
#ifdef OSD_CALLS_CMS

View File

@ -35,6 +35,8 @@ uint8_t cliMode = 0;
#include "build/debug.h"
#include "build/version.h"
#include "cms/cms.h"
#include "common/axis.h"
#include "common/color.h"
#include "common/maths.h"
@ -70,7 +72,6 @@ uint8_t cliMode = 0;
#include "io/flashfs.h"
#include "io/beeper.h"
#include "io/asyncfatfs/asyncfatfs.h"
#include "io/cms.h"
#include "io/osd.h"
#include "io/vtx.h"
@ -228,7 +229,7 @@ static const char * const featureNames[] = {
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "OSD",
"BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE",
" ", "VTX", "RX_SPI", "SOFTSPI", "CANVAS", NULL
" ", "VTX", "RX_SPI", "SOFTSPI", "MSP_OSD", NULL
};
// sync this with rxFailsafeChannelMode_e

View File

@ -29,8 +29,9 @@
#include "common/maths.h"
#include "common/printf.h"
#include "drivers/nvic.h"
#include "cms/cms.h"
#include "drivers/nvic.h"
#include "drivers/sensor.h"
#include "drivers/system.h"
#include "drivers/dma.h"
@ -74,8 +75,6 @@
#include "rx/rx.h"
#include "rx/spektrum.h"
#include "io/cms.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/flashfs.h"
@ -89,7 +88,7 @@
#include "io/serial_cli.h"
#include "io/transponder_ir.h"
#include "io/osd.h"
#include "io/canvas.h"
#include "io/displayport_msp.h"
#include "io/vtx.h"
#include "scheduler/scheduler.h"
@ -461,9 +460,9 @@ void init(void)
mspFcInit();
mspSerialInit();
#ifdef CANVAS
if (feature(FEATURE_CANVAS)) {
cmsDisplayPortRegister(canvasInit());
#ifdef USE_MSP_DISPLAYPORT
if (feature(FEATURE_MSP_OSD)) {
cmsDisplayPortRegister(displayPortMspInit());
}
#endif

View File

@ -216,8 +216,8 @@
#define MSP_OSD_VIDEO_CONFIG 180
#define MSP_SET_OSD_VIDEO_CONFIG 181
// External OSD canvas mode messages
#define MSP_CANVAS 182
// External OSD displayport mode messages
#define MSP_DISPLAYPORT 182
//
// Multwii original MSP commands

View File

@ -97,8 +97,8 @@
#define CMS
#define CMS_MAX_DEVICE 4
// Use external OSD to run CMS
#define CANVAS
// Use external display to run CMS
#define USE_MSP_DISPLAYPORT
// USE I2C OLED display to run CMS
#define OLEDCMS

View File

@ -71,7 +71,7 @@
//#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_ST0_HANDLER
#define CMS
#define CANVAS
#define USE_MSP_OSD
//#define PITOT
//#define USE_PITOT_MS4525

View File

@ -6,6 +6,4 @@ TARGET_SRC = \
drivers/accgyro_mpu6500.c \
drivers/accgyro_spi_mpu6500.c \
drivers/barometer_ms5611.c \
drivers/compass_hmc5883l.c \
io/cms.c \
io/canvas.c
drivers/compass_hmc5883l.c

View File

@ -144,8 +144,8 @@
// Configuratoin Menu System
#define CMS
// Use external OSD to run CMS
#define CANVAS
// Use external display to run CMS
#define USE_MSP_DISPLAYPORT
// USE I2C OLED display to run CMS
#define OLEDCMS

View File

@ -145,8 +145,8 @@
// Configuratoin Menu System
#define CMS
// Use external OSD to run CMS
#define CANVAS
// Use external display to run CMS
#define USE_MSP_DISPLAYPORT
// USE I2C OLED display to run CMS
#define OLEDCMS