1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-26 01:35:35 +03:00

Brute force grafting

Attempt to brutally graft BF3.1’s OSD, CMS, DISPLAYPORT, DASHBOARD,
MSP_DISPLAYPORT onto INAV-1.4.

With this first cut, integrated OSD (based on MAX7456) and CMS over the
OSD is working.
This commit is contained in:
jflyper 2016-11-09 22:26:56 +09:00
parent 9baac451de
commit 8dbef28d81
42 changed files with 5325 additions and 4 deletions

870
src/main/cms/cms.c Normal file
View file

@ -0,0 +1,870 @@
/*
* 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/>.
*/
/*
Original OSD code created by Marcin Baliniak
OSD-CMS separation by jflyper
CMS-displayPort separation by jflyper and martinbudden
*/
//#define CMS_MENU_DEBUG // For external menu content creators
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <ctype.h>
#include "platform.h"
#ifdef CMS
#include "build/build_config.h"
#include "build/debug.h"
#include "build/version.h"
#include "cms/cms.h"
#include "cms/cms_menu_builtin.h"
#include "cms/cms_types.h"
#include "common/typeconversion.h"
#include "drivers/system.h"
#include "config/config.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "common/axis.h"
#include "io/gimbal.h"
#include "flight/pid.h"
#include "flight/mixer.h"
#include "flight/servos.h"
#include "config/config_profile.h"
#include "config/config_master.h"
#include "config/feature.h"
// For VISIBLE* (Actually, included by config_master.h)
#include "io/osd.h"
// DisplayPort management
#ifndef CMS_MAX_DEVICE
#define CMS_MAX_DEVICE 4
#endif
static displayPort_t *pCurrentDisplay;
static displayPort_t *cmsDisplayPorts[CMS_MAX_DEVICE];
static int cmsDeviceCount;
static int cmsCurrentDevice;
bool cmsDisplayPortRegister(displayPort_t *pDisplay)
{
if (cmsDeviceCount == CMS_MAX_DEVICE)
return false;
cmsDisplayPorts[cmsDeviceCount++] = pDisplay;
return true;
}
static displayPort_t *cmsDisplayPortSelectCurrent(void)
{
if (cmsDeviceCount == 0)
return NULL;
if (cmsCurrentDevice < 0)
cmsCurrentDevice = 0;
return cmsDisplayPorts[cmsCurrentDevice];
}
static displayPort_t *cmsDisplayPortSelectNext(void)
{
if (cmsDeviceCount == 0)
return NULL;
cmsCurrentDevice = (cmsCurrentDevice + 1) % cmsDeviceCount; // -1 Okay
return cmsDisplayPorts[cmsCurrentDevice];
}
#define CMS_UPDATE_INTERVAL_US 50000 // Interval of key scans (microsec)
#define CMS_POLL_INTERVAL_US 100000 // Interval of polling dynamic values (microsec)
// XXX LEFT_MENU_COLUMN and RIGHT_MENU_COLUMN must be adjusted
// dynamically depending on size of the active output device,
// or statically to accomodate sizes of all supported devices.
//
// Device characteristics
// OLED
// 21 cols x 8 rows
// 128x64 with 5x7 (6x8) : 21 cols x 8 rows
// MAX7456 (PAL)
// 30 cols x 16 rows
// MAX7456 (NTSC)
// 30 cols x 13 rows
// HoTT Telemetry Screen
// 21 cols x 8 rows
//
#define LEFT_MENU_COLUMN 1
#define RIGHT_MENU_COLUMN(p) ((p)->cols - 8)
#define MAX_MENU_ITEMS(p) ((p)->rows - 2)
static bool cmsInMenu = false;
STATIC_UNIT_TESTED const CMS_Menu *currentMenu; // Points to top entry of the current page
// XXX Does menu backing support backing into second page???
static const CMS_Menu *menuStack[10]; // Stack to save menu transition
static uint8_t menuStackHistory[10];// cursorRow in a stacked menu
static uint8_t menuStackIdx = 0;
static OSD_Entry *pageTop; // Points to top entry of the current page
static OSD_Entry *pageTopAlt; // Only 2 pages are allowed (for now)
static uint8_t maxRow; // Max row in the current page
static int8_t cursorRow;
#ifdef CMS_MENU_DEBUG // For external menu content creators
static char menuErrLabel[21 + 1] = "RANDOM DATA";
static OSD_Entry menuErrEntries[] = {
{ "BROKEN MENU", OME_Label, NULL, NULL, 0 },
{ menuErrLabel, OME_Label, NULL, NULL, 0 },
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
};
static CMS_Menu menuErr = {
"MENUERR",
OME_MENU,
NULL,
NULL,
NULL,
menuErrEntries,
};
#endif
// Stick/key detection
#define IS_HI(X) (rcData[X] > 1750)
#define IS_LO(X) (rcData[X] < 1250)
#define IS_MID(X) (rcData[X] > 1250 && rcData[X] < 1750)
//key definiotion because API provide menu navigation over MSP/GUI app - not used NOW
#define KEY_ENTER 0
#define KEY_UP 1
#define KEY_DOWN 2
#define KEY_LEFT 3
#define KEY_RIGHT 4
#define KEY_ESC 5
#define BUTTON_TIME 250 // msec
#define BUTTON_PAUSE 500 // msec
static void cmsUpdateMaxRow(displayPort_t *instance)
{
maxRow = 0;
for (const OSD_Entry *ptr = pageTop; ptr->type != OME_END; ptr++) {
maxRow++;
}
if (maxRow > MAX_MENU_ITEMS(instance)) {
maxRow = MAX_MENU_ITEMS(instance);
}
maxRow--;
}
static void cmsFormatFloat(int32_t value, char *floatString)
{
uint8_t k;
// np. 3450
itoa(100000 + value, floatString, 10); // Create string from abs of integer value
// 103450
floatString[0] = floatString[1];
floatString[1] = floatString[2];
floatString[2] = '.';
// 03.450
// usuwam koncowe zera i kropke
// Keep the first decimal place
for (k = 5; k > 3; k--)
if (floatString[k] == '0' || floatString[k] == '.')
floatString[k] = 0;
else
break;
// oraz zero wiodonce
if (floatString[0] == '0')
floatString[0] = ' ';
}
static void cmsPadToSize(char *buf, int size)
{
int i;
for (i = 0 ; i < size ; i++) {
if (buf[i] == 0)
break;
}
for ( ; i < size ; i++) {
buf[i] = ' ';
}
buf[size] = 0;
}
static int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row)
{
char buff[10];
int cnt = 0;
switch (p->type) {
case OME_String:
if (IS_PRINTVALUE(p) && p->data) {
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, p->data);
CLR_PRINTVALUE(p);
}
break;
case OME_Submenu:
case OME_Funcall:
if (IS_PRINTVALUE(p)) {
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, ">");
CLR_PRINTVALUE(p);
}
break;
case OME_Bool:
if (IS_PRINTVALUE(p) && p->data) {
if (*((uint8_t *)(p->data))) {
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, "YES");
} else {
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, "NO ");
}
CLR_PRINTVALUE(p);
}
break;
case OME_TAB: {
if (IS_PRINTVALUE(p)) {
OSD_TAB_t *ptr = p->data;
//cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay) - 5, row, (char *)ptr->names[*ptr->val]);
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, (char *)ptr->names[*ptr->val]);
CLR_PRINTVALUE(p);
}
break;
}
#ifdef OSD
case OME_VISIBLE:
if (IS_PRINTVALUE(p) && p->data) {
uint32_t address = (uint32_t)p->data;
uint16_t *val;
val = (uint16_t *)address;
if (VISIBLE(*val)) {
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, "YES");
} else {
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, "NO ");
}
CLR_PRINTVALUE(p);
}
break;
#endif
case OME_UINT8:
if (IS_PRINTVALUE(p) && p->data) {
OSD_UINT8_t *ptr = p->data;
itoa(*ptr->val, buff, 10);
cmsPadToSize(buff, 5);
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, buff);
CLR_PRINTVALUE(p);
}
break;
case OME_INT8:
if (IS_PRINTVALUE(p) && p->data) {
OSD_INT8_t *ptr = p->data;
itoa(*ptr->val, buff, 10);
cmsPadToSize(buff, 5);
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, buff);
CLR_PRINTVALUE(p);
}
break;
case OME_UINT16:
if (IS_PRINTVALUE(p) && p->data) {
OSD_UINT16_t *ptr = p->data;
itoa(*ptr->val, buff, 10);
cmsPadToSize(buff, 5);
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, buff);
CLR_PRINTVALUE(p);
}
break;
case OME_INT16:
if (IS_PRINTVALUE(p) && p->data) {
OSD_UINT16_t *ptr = p->data;
itoa(*ptr->val, buff, 10);
cmsPadToSize(buff, 5);
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, buff);
CLR_PRINTVALUE(p);
}
break;
case OME_FLOAT:
if (IS_PRINTVALUE(p) && p->data) {
OSD_FLOAT_t *ptr = p->data;
cmsFormatFloat(*ptr->val * ptr->multipler, buff);
cmsPadToSize(buff, 5);
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay) - 1, row, buff); // XXX One char left ???
CLR_PRINTVALUE(p);
}
break;
case OME_Label:
if (IS_PRINTVALUE(p) && p->data) {
// A label with optional string, immediately following text
cnt = displayWrite(pDisplay, LEFT_MENU_COLUMN + 2 + strlen(p->text), row, p->data);
CLR_PRINTVALUE(p);
}
break;
case OME_OSD_Exit:
case OME_END:
case OME_Back:
break;
case OME_MENU:
// Fall through
default:
#ifdef CMS_MENU_DEBUG
// Shouldn't happen. Notify creator of this menu content.
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, "BADENT");
#endif
break;
}
return cnt;
}
static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs)
{
if (!pageTop)
return;
uint8_t i;
OSD_Entry *p;
uint8_t top = (pDisplay->rows - maxRow) / 2 - 1;
// Polled (dynamic) value display denominator.
bool drawPolled = false;
static uint32_t lastPolledUs = 0;
if (currentTimeUs > lastPolledUs + CMS_POLL_INTERVAL_US) {
drawPolled = true;
lastPolledUs = currentTimeUs;
}
uint32_t room = displayTxBytesFree(pDisplay);
if (pDisplay->cleared) {
for (p = pageTop, i= 0; p->type != OME_END; p++, i++) {
SET_PRINTLABEL(p);
SET_PRINTVALUE(p);
}
if (i > MAX_MENU_ITEMS(pDisplay)) // max per page
{
pageTopAlt = pageTop + MAX_MENU_ITEMS(pDisplay);
if (pageTopAlt->type == OME_END)
pageTopAlt = NULL;
}
pDisplay->cleared = false;
} else if (drawPolled) {
for (p = pageTop ; p <= pageTop + maxRow ; p++) {
if (IS_DYNAMIC(p))
SET_PRINTVALUE(p);
}
}
// Cursor manipulation
while ((pageTop + cursorRow)->type == OME_Label) // skip label
cursorRow++;
if (pDisplay->cursorRow >= 0 && cursorRow != pDisplay->cursorRow) {
room -= displayWrite(pDisplay, LEFT_MENU_COLUMN, pDisplay->cursorRow + top, " ");
}
if (room < 30)
return;
if (pDisplay->cursorRow != cursorRow) {
room -= displayWrite(pDisplay, LEFT_MENU_COLUMN, cursorRow + top, " >");
pDisplay->cursorRow = cursorRow;
}
if (room < 30)
return;
// Print text labels
for (i = 0, p = pageTop; i < MAX_MENU_ITEMS(pDisplay) && p->type != OME_END; i++, p++) {
if (IS_PRINTLABEL(p)) {
uint8_t coloff = LEFT_MENU_COLUMN;
coloff += (p->type == OME_Label) ? 1 : 2;
room -= displayWrite(pDisplay, coloff, i + top, p->text);
CLR_PRINTLABEL(p);
if (room < 30)
return;
}
}
// Print values
// XXX Polled values at latter positions in the list may not be
// XXX printed if not enough room in the middle of the list.
for (i = 0, p = pageTop; i < MAX_MENU_ITEMS(pDisplay) && p->type != OME_END; i++, p++) {
if (IS_PRINTVALUE(p)) {
room -= cmsDrawMenuEntry(pDisplay, p, top + i);
if (room < 30)
return;
}
}
}
long cmsMenuChange(displayPort_t *pDisplay, const void *ptr)
{
CMS_Menu *pMenu = (CMS_Menu *)ptr;
if (pMenu) {
#ifdef CMS_MENU_DEBUG
if (pMenu->GUARD_type != OME_MENU) {
// ptr isn't pointing to a CMS_Menu.
if (pMenu->GUARD_type <= OME_MAX) {
strncpy(menuErrLabel, pMenu->GUARD_text, sizeof(menuErrLabel) - 1);
} else {
strncpy(menuErrLabel, "LABEL UNKNOWN", sizeof(menuErrLabel) - 1);
}
pMenu = &menuErr;
}
#endif
// Stack the current menu and move to a new menu.
// The (pMenu == curretMenu) case occurs when reopening for display sw
if (pMenu != currentMenu) {
menuStack[menuStackIdx] = currentMenu;
cursorRow += pageTop - currentMenu->entries; // Convert cursorRow to absolute value
menuStackHistory[menuStackIdx] = cursorRow;
menuStackIdx++;
currentMenu = pMenu;
cursorRow = 0;
if (pMenu->onEnter)
pMenu->onEnter();
}
pageTop = currentMenu->entries;
pageTopAlt = NULL;
displayClear(pDisplay);
cmsUpdateMaxRow(pDisplay);
}
return 0;
}
STATIC_UNIT_TESTED long cmsMenuBack(displayPort_t *pDisplay)
{
// Let onExit function decide whether to allow exit or not.
if (currentMenu->onExit && currentMenu->onExit(pageTop + cursorRow) < 0)
return -1;
if (menuStackIdx) {
displayClear(pDisplay);
menuStackIdx--;
currentMenu = menuStack[menuStackIdx];
cursorRow = menuStackHistory[menuStackIdx];
// cursorRow is absolute offset of a focused entry when stacked.
// Convert it back to page and relative offset.
pageTop = currentMenu->entries; // Temporary for cmsUpdateMaxRow()
cmsUpdateMaxRow(pDisplay);
if (cursorRow > maxRow) {
// Cursor was in the second page.
pageTopAlt = currentMenu->entries;
pageTop = pageTopAlt + maxRow + 1;
cursorRow -= (maxRow + 1);
cmsUpdateMaxRow(pDisplay); // Update maxRow for the second page
}
}
return 0;
}
STATIC_UNIT_TESTED void cmsMenuOpen(void)
{
if (!cmsInMenu) {
// New open
pCurrentDisplay = cmsDisplayPortSelectCurrent();
if (!pCurrentDisplay)
return;
cmsInMenu = true;
currentMenu = &menuMain;
DISABLE_ARMING_FLAG(OK_TO_ARM);
} else {
// Switch display
displayPort_t *pNextDisplay = cmsDisplayPortSelectNext();
if (pNextDisplay != pCurrentDisplay) {
displayRelease(pCurrentDisplay);
pCurrentDisplay = pNextDisplay;
} else {
return;
}
}
displayGrab(pCurrentDisplay); // grab the display for use by the CMS
cmsMenuChange(pCurrentDisplay, currentMenu);
}
static void cmsTraverseGlobalExit(const CMS_Menu *pMenu)
{
for (const OSD_Entry *p = pMenu->entries; p->type != OME_END ; p++) {
if (p->type == OME_Submenu) {
cmsTraverseGlobalExit(p->data);
}
}
if (pMenu->onGlobalExit) {
pMenu->onGlobalExit();
}
}
long cmsMenuExit(displayPort_t *pDisplay, const void *ptr)
{
if (ptr) {
displayClear(pDisplay);
displayWrite(pDisplay, 5, 3, "REBOOTING...");
displayResync(pDisplay); // Was max7456RefreshAll(); why at this timing?
stopMotors();
stopPwmAllMotors();
delay(200);
cmsTraverseGlobalExit(&menuMain);
if (currentMenu->onExit)
currentMenu->onExit((OSD_Entry *)NULL); // Forced exit
saveConfigAndNotify();
}
cmsInMenu = false;
displayRelease(pDisplay);
currentMenu = NULL;
if (ptr)
systemReset();
ENABLE_ARMING_FLAG(OK_TO_ARM);
return 0;
}
STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
{
uint16_t res = BUTTON_TIME;
OSD_Entry *p;
if (!currentMenu)
return res;
if (key == KEY_ESC) {
cmsMenuBack(pDisplay);
return BUTTON_PAUSE;
}
if (key == KEY_DOWN) {
if (cursorRow < maxRow) {
cursorRow++;
} else {
if (pageTopAlt) { // we have another page
displayClear(pDisplay);
p = pageTopAlt;
pageTopAlt = pageTop;
pageTop = (OSD_Entry *)p;
cmsUpdateMaxRow(pDisplay);
}
cursorRow = 0; // Goto top in any case
}
}
if (key == KEY_UP) {
cursorRow--;
if ((pageTop + cursorRow)->type == OME_Label && cursorRow > 0)
cursorRow--;
if (cursorRow == -1 || (pageTop + cursorRow)->type == OME_Label) {
if (pageTopAlt) {
displayClear(pDisplay);
p = pageTopAlt;
pageTopAlt = pageTop;
pageTop = (OSD_Entry *)p;
cmsUpdateMaxRow(pDisplay);
}
cursorRow = maxRow; // Goto bottom in any case
}
}
if (key == KEY_DOWN || key == KEY_UP)
return res;
p = pageTop + cursorRow;
switch (p->type) {
case OME_Submenu:
case OME_Funcall:
case OME_OSD_Exit:
if (p->func && key == KEY_RIGHT) {
p->func(pDisplay, p->data);
res = BUTTON_PAUSE;
}
break;
case OME_Back:
cmsMenuBack(pDisplay);
res = BUTTON_PAUSE;
break;
case OME_Bool:
if (p->data) {
uint8_t *val = p->data;
if (key == KEY_RIGHT)
*val = 1;
else
*val = 0;
SET_PRINTVALUE(p);
}
break;
#ifdef OSD
case OME_VISIBLE:
if (p->data) {
uint32_t address = (uint32_t)p->data;
uint16_t *val;
val = (uint16_t *)address;
if (key == KEY_RIGHT)
*val |= VISIBLE_FLAG;
else
*val %= ~VISIBLE_FLAG;
SET_PRINTVALUE(p);
}
break;
#endif
case OME_UINT8:
case OME_FLOAT:
if (p->data) {
OSD_UINT8_t *ptr = p->data;
if (key == KEY_RIGHT) {
if (*ptr->val < ptr->max)
*ptr->val += ptr->step;
}
else {
if (*ptr->val > ptr->min)
*ptr->val -= ptr->step;
}
SET_PRINTVALUE(p);
if (p->func) {
p->func(pDisplay, p);
}
}
break;
case OME_TAB:
if (p->type == OME_TAB) {
OSD_TAB_t *ptr = p->data;
if (key == KEY_RIGHT) {
if (*ptr->val < ptr->max)
*ptr->val += 1;
}
else {
if (*ptr->val > 0)
*ptr->val -= 1;
}
if (p->func)
p->func(pDisplay, p->data);
SET_PRINTVALUE(p);
}
break;
case OME_INT8:
if (p->data) {
OSD_INT8_t *ptr = p->data;
if (key == KEY_RIGHT) {
if (*ptr->val < ptr->max)
*ptr->val += ptr->step;
}
else {
if (*ptr->val > ptr->min)
*ptr->val -= ptr->step;
}
SET_PRINTVALUE(p);
if (p->func) {
p->func(pDisplay, p);
}
}
break;
case OME_UINT16:
if (p->data) {
OSD_UINT16_t *ptr = p->data;
if (key == KEY_RIGHT) {
if (*ptr->val < ptr->max)
*ptr->val += ptr->step;
}
else {
if (*ptr->val > ptr->min)
*ptr->val -= ptr->step;
}
SET_PRINTVALUE(p);
if (p->func) {
p->func(pDisplay, p);
}
}
break;
case OME_INT16:
if (p->data) {
OSD_INT16_t *ptr = p->data;
if (key == KEY_RIGHT) {
if (*ptr->val < ptr->max)
*ptr->val += ptr->step;
}
else {
if (*ptr->val > ptr->min)
*ptr->val -= ptr->step;
}
SET_PRINTVALUE(p);
if (p->func) {
p->func(pDisplay, p);
}
}
break;
case OME_String:
break;
case OME_Label:
case OME_END:
break;
case OME_MENU:
// Shouldn't happen
break;
}
return res;
}
static void cmsUpdate(uint32_t currentTimeUs)
{
static int16_t rcDelayMs = BUTTON_TIME;
static uint32_t lastCalledMs = 0;
static uint32_t lastCmsHeartBeatMs = 0;
const uint32_t currentTimeMs = currentTimeUs / 1000;
if (!cmsInMenu) {
// Detect menu invocation
if (IS_MID(THROTTLE) && IS_LO(YAW) && IS_HI(PITCH) && !ARMING_FLAG(ARMED)) {
cmsMenuOpen();
rcDelayMs = BUTTON_PAUSE; // Tends to overshoot if BUTTON_TIME
}
} else {
uint8_t key = 0;
if (rcDelayMs > 0) {
rcDelayMs -= (currentTimeMs - lastCalledMs);
}
else if (IS_MID(THROTTLE) && IS_LO(YAW) && IS_HI(PITCH) && !ARMING_FLAG(ARMED)) {
// Double enter = display switching
cmsMenuOpen();
rcDelayMs = BUTTON_PAUSE;
}
else if (IS_HI(PITCH)) {
key = KEY_UP;
rcDelayMs = BUTTON_TIME;
}
else if (IS_LO(PITCH)) {
key = KEY_DOWN;
rcDelayMs = BUTTON_TIME;
}
else if (IS_LO(ROLL)) {
key = KEY_LEFT;
rcDelayMs = BUTTON_TIME;
}
else if (IS_HI(ROLL)) {
key = KEY_RIGHT;
rcDelayMs = BUTTON_TIME;
}
else if (IS_HI(YAW) || IS_LO(YAW))
{
key = KEY_ESC;
rcDelayMs = BUTTON_TIME;
}
//lastCalled = currentTime;
if (key) {
rcDelayMs = cmsHandleKey(pCurrentDisplay, key);
return;
}
cmsDrawMenu(pCurrentDisplay, currentTimeUs);
if (currentTimeMs > lastCmsHeartBeatMs + 500) {
// Heart beat for external CMS display device @ 500msec
// (Timeout @ 1000msec)
displayHeartbeat(pCurrentDisplay);
lastCmsHeartBeatMs = currentTimeMs;
}
}
lastCalledMs = currentTimeMs;
}
void cmsHandler(uint32_t currentTime)
{
if (cmsDeviceCount < 0)
return;
static uint32_t lastCalled = 0;
if (currentTime >= lastCalled + CMS_UPDATE_INTERVAL_US) {
lastCalled = currentTime;
cmsUpdate(currentTime);
}
}
void cmsInit(void)
{
cmsDeviceCount = 0;
cmsCurrentDevice = -1;
}
#endif // CMS

17
src/main/cms/cms.h Normal file
View file

@ -0,0 +1,17 @@
#pragma once
#include "drivers/display.h"
// Device management
bool cmsDisplayPortRegister(displayPort_t *pDisplay);
// For main.c and scheduler
void cmsInit(void);
void cmsHandler(uint32_t currentTime);
long cmsMenuChange(displayPort_t *pPort, const void *ptr);
long cmsMenuExit(displayPort_t *pPort, const void *ptr);
#define CMS_STARTUP_HELP_TEXT1 "MENU: THR MID"
#define CMS_STARTUP_HELP_TEXT2 "+ YAW LEFT"
#define CMS_STARTUP_HELP_TEXT3 "+ PITCH UP"

View file

@ -0,0 +1,120 @@
/*
* 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/>.
*/
//
// CMS things for blackbox and flashfs.
//
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <ctype.h>
#include "platform.h"
#include "build/version.h"
#ifdef CMS
#include "drivers/system.h"
#include "cms/cms.h"
#include "cms/cms_types.h"
#include "cms/cms_menu_blackbox.h"
#include "common/axis.h"
#include "io/gimbal.h"
#include "flight/pid.h"
#include "flight/mixer.h"
#include "flight/servos.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
#include "config/feature.h"
#include "io/flashfs.h"
#ifdef USE_FLASHFS
static long cmsx_EraseFlash(displayPort_t *pDisplay, const void *ptr)
{
UNUSED(ptr);
displayClear(pDisplay);
displayWrite(pDisplay, 5, 3, "ERASING FLASH...");
displayResync(pDisplay); // Was max7456RefreshAll(); Why at this timing?
flashfsEraseCompletely();
while (!flashfsIsReady()) {
delay(100);
}
displayClear(pDisplay);
displayResync(pDisplay); // Was max7456RefreshAll(); wedges during heavy SPI?
return 0;
}
#endif // USE_FLASHFS
static bool featureRead = false;
static uint8_t cmsx_FeatureBlackbox;
static long cmsx_Blackbox_FeatureRead(void)
{
if (!featureRead) {
cmsx_FeatureBlackbox = feature(FEATURE_BLACKBOX) ? 1 : 0;
featureRead = true;
}
return 0;
}
static long cmsx_Blackbox_FeatureWriteback(void)
{
if (cmsx_FeatureBlackbox)
featureSet(FEATURE_BLACKBOX);
else
featureClear(FEATURE_BLACKBOX);
return 0;
}
static OSD_Entry cmsx_menuBlackboxEntries[] =
{
{ "-- BLACKBOX --", OME_Label, NULL, NULL, 0},
{ "ENABLED", OME_Bool, NULL, &cmsx_FeatureBlackbox, 0 },
{ "RATE DENOM", OME_UINT8, NULL, &(OSD_UINT8_t){ &masterConfig.blackbox_rate_denom,1,32,1 }, 0 },
#ifdef USE_FLASHFS
{ "ERASE FLASH", OME_Funcall, cmsx_EraseFlash, NULL, 0 },
#endif // USE_FLASHFS
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
};
CMS_Menu cmsx_menuBlackbox = {
.GUARD_text = "MENUBB",
.GUARD_type = OME_MENU,
.onEnter = cmsx_Blackbox_FeatureRead,
.onExit = NULL,
.onGlobalExit = cmsx_Blackbox_FeatureWriteback,
.entries = cmsx_menuBlackboxEntries
};
#endif

View file

@ -0,0 +1,20 @@
/*
* 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/>.
*/
#pragma once
extern CMS_Menu cmsx_menuBlackbox;

View file

@ -0,0 +1,143 @@
/*
* 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/>.
*/
//
// Built-in menu contents and support functions
//
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <ctype.h>
#include "platform.h"
#ifdef CMS
#include "build/version.h"
#include "drivers/system.h"
#include "cms/cms.h"
#include "cms/cms_types.h"
#include "cms/cms_menu_builtin.h"
// Sub menus
#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"
#include "cms/cms_menu_misc.h"
// Info
static char infoGitRev[GIT_SHORT_REVISION_LENGTH];
static char infoTargetName[] = __TARGET__;
#include "msp/msp_protocol.h" // XXX for FC identification... not available elsewhere
static long cmsx_InfoInit(void)
{
for (int i = 0 ; i < GIT_SHORT_REVISION_LENGTH ; i++) {
if (shortGitRevision[i] >= 'a' && shortGitRevision[i] <= 'f')
infoGitRev[i] = shortGitRevision[i] - 'a' + 'A';
else
infoGitRev[i] = shortGitRevision[i];
}
return 0;
}
static OSD_Entry menuInfoEntries[] = {
{ "--- INFO ---", OME_Label, NULL, NULL, 0 },
{ "FWID", OME_String, NULL, INAV_IDENTIFIER, 0 },
{ "FWVER", OME_String, NULL, FC_VERSION_STRING, 0 },
{ "GITREV", OME_String, NULL, infoGitRev, 0 },
{ "TARGET", OME_String, NULL, infoTargetName, 0 },
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
};
static CMS_Menu menuInfo = {
.GUARD_text = "MENUINFO",
.GUARD_type = OME_MENU,
.onEnter = cmsx_InfoInit,
.onExit = NULL,
.onGlobalExit = NULL,
.entries = menuInfoEntries
};
// Features
static OSD_Entry menuFeaturesEntries[] =
{
{"--- FEATURES ---", OME_Label, NULL, NULL, 0},
{"BLACKBOX", OME_Submenu, cmsMenuChange, &cmsx_menuBlackbox, 0},
#if defined(VTX) || defined(USE_RTC6705)
{"VTX", OME_Submenu, cmsMenuChange, &cmsx_menuVtx, 0},
#endif // VTX || USE_RTC6705
#ifdef LED_STRIP
{"LED STRIP", OME_Submenu, cmsMenuChange, &cmsx_menuLedstrip, 0},
#endif // LED_STRIP
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
static CMS_Menu menuFeatures = {
.GUARD_text = "MENUFEATURES",
.GUARD_type = OME_MENU,
.onEnter = NULL,
.onExit = NULL,
.onGlobalExit = NULL,
.entries = menuFeaturesEntries,
};
// Main
static OSD_Entry menuMainEntries[] =
{
{"-- MAIN --", OME_Label, NULL, NULL, 0},
{"PROFILE", OME_Submenu, cmsMenuChange, &cmsx_menuImu, 0},
{"FEATURES", OME_Submenu, cmsMenuChange, &menuFeatures, 0},
#ifdef OSD
{"SCR LAYOUT", OME_Submenu, cmsMenuChange, &cmsx_menuOsdLayout, 0},
{"ALARMS", OME_Submenu, cmsMenuChange, &cmsx_menuAlarms, 0},
#endif
{"FC&FW INFO", OME_Submenu, cmsMenuChange, &menuInfo, 0},
{"MISC", OME_Submenu, cmsMenuChange, &cmsx_menuMisc, 0},
{"SAVE&REBOOT", OME_OSD_Exit, cmsMenuExit, (void*)1, 0},
{"EXIT", OME_OSD_Exit, cmsMenuExit, (void*)0, 0},
#ifdef CMS_MENU_DEBUG
{"ERR SAMPLE", OME_Submenu, cmsMenuChange, &menuInfoEntries[0], 0},
#endif
{NULL,OME_END, NULL, NULL, 0}
};
CMS_Menu menuMain = {
.GUARD_text = "MENUMAIN",
.GUARD_type = OME_MENU,
.onEnter = NULL,
.onExit = NULL,
.onGlobalExit = NULL,
.entries = menuMainEntries,
};
#endif

View file

@ -0,0 +1,22 @@
/*
* 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/>.
*/
#pragma once
#include "cms/cms_types.h"
extern CMS_Menu menuMain;

402
src/main/cms/cms_menu_imu.c Normal file
View file

@ -0,0 +1,402 @@
/*
* 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/>.
*/
// Menu contents for PID, RATES, RC preview, misc
// Should be part of the relevant .c file.
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <ctype.h>
#include "platform.h"
#ifdef CMS
#include "build/version.h"
#include "build/build_config.h"
//#include "drivers/system.h"
//#include "common/typeconversion.h"
#include "cms/cms.h"
#include "cms/cms_types.h"
#include "cms/cms_menu_imu.h"
#include "common/axis.h"
#include "io/gimbal.h"
#include "flight/pid.h"
#include "flight/mixer.h"
#include "flight/servos.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
#include "config/feature.h"
//
// PID
//
static uint8_t tmpProfileIndex;
static uint8_t profileIndex;
static char profileIndexString[] = " p";
static uint8_t tempPid[3][3];
#ifdef NOT_YET
static uint8_t tmpRateProfileIndex;
static uint8_t rateProfileIndex;
static char rateProfileIndexString[] = " p-r";
static controlRateConfig_t rateProfile;
#endif
static long cmsx_menuImu_onEnter(void)
{
profileIndex = masterConfig.current_profile_index;
tmpProfileIndex = profileIndex + 1;
#ifdef NOT_YET
rateProfileIndex = masterConfig.profile[profileIndex].activeRateProfile;
tmpRateProfileIndex = rateProfileIndex + 1;
#endif
return 0;
}
static long cmsx_menuImu_onExit(const OSD_Entry *self)
{
UNUSED(self);
masterConfig.current_profile_index = profileIndex;
#ifdef NOT_YET
masterConfig.profile[profileIndex].activeRateProfile = rateProfileIndex;
#endif
return 0;
}
static long cmsx_profileIndexOnChange(displayPort_t *displayPort, const void *ptr)
{
UNUSED(displayPort);
UNUSED(ptr);
profileIndex = tmpProfileIndex - 1;
return 0;
}
#ifdef NOT_YET
static long cmsx_rateProfileIndexOnChange(displayPort_t *displayPort, const void *ptr)
{
UNUSED(displayPort);
UNUSED(ptr);
rateProfileIndex = tmpRateProfileIndex - 1;
return 0;
}
#endif
static long cmsx_PidRead(void)
{
for (uint8_t i = 0; i < 3; i++) {
tempPid[i][0] = masterConfig.profile[profileIndex].pidProfile.P8[i];
tempPid[i][1] = masterConfig.profile[profileIndex].pidProfile.I8[i];
tempPid[i][2] = masterConfig.profile[profileIndex].pidProfile.D8[i];
}
return 0;
}
static long cmsx_PidOnEnter(void)
{
profileIndexString[1] = '0' + tmpProfileIndex;
cmsx_PidRead();
return 0;
}
static long cmsx_PidWriteback(const OSD_Entry *self)
{
UNUSED(self);
for (uint8_t i = 0; i < 3; i++) {
masterConfig.profile[profileIndex].pidProfile.P8[i] = tempPid[i][0];
masterConfig.profile[profileIndex].pidProfile.I8[i] = tempPid[i][1];
masterConfig.profile[profileIndex].pidProfile.D8[i] = tempPid[i][2];
}
return 0;
}
static OSD_Entry cmsx_menuPidEntries[] =
{
{ "-- PID --", OME_Label, NULL, profileIndexString, 0},
{ "ROLL P", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDROLL][0], 0, 200, 1 }, 0 },
{ "ROLL I", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDROLL][1], 0, 200, 1 }, 0 },
{ "ROLL D", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDROLL][2], 0, 200, 1 }, 0 },
{ "PITCH P", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDPITCH][0], 0, 200, 1 }, 0 },
{ "PITCH I", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDPITCH][1], 0, 200, 1 }, 0 },
{ "PITCH D", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDPITCH][2], 0, 200, 1 }, 0 },
{ "YAW P", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDYAW][0], 0, 200, 1 }, 0 },
{ "YAW I", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDYAW][1], 0, 200, 1 }, 0 },
{ "YAW D", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDYAW][2], 0, 200, 1 }, 0 },
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
};
static CMS_Menu cmsx_menuPid = {
.GUARD_text = "XPID",
.GUARD_type = OME_MENU,
.onEnter = cmsx_PidOnEnter,
.onExit = cmsx_PidWriteback,
.onGlobalExit = NULL,
.entries = cmsx_menuPidEntries
};
#ifdef NOT_YET
//
// Rate & Expo
//
static long cmsx_RateProfileRead(void)
{
memcpy(&rateProfile, &masterConfig.profile[profileIndex].controlRateProfile[rateProfileIndex], sizeof(controlRateConfig_t));
return 0;
}
static long cmsx_RateProfileWriteback(const OSD_Entry *self)
{
UNUSED(self);
memcpy(&masterConfig.profile[profileIndex].controlRateProfile[rateProfileIndex], &rateProfile, sizeof(controlRateConfig_t));
return 0;
}
static long cmsx_RateProfileOnEnter(void)
{
rateProfileIndexString[1] = '0' + tmpProfileIndex;
rateProfileIndexString[3] = '0' + tmpRateProfileIndex;
cmsx_RateProfileRead();
return 0;
}
static OSD_Entry cmsx_menuRateProfileEntries[] =
{
{ "-- RATE --", OME_Label, NULL, rateProfileIndexString, 0 },
{ "RC RATE", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcRate8, 0, 255, 1, 10 }, 0 },
{ "RC YAW RATE", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcYawRate8, 0, 255, 1, 10 }, 0 },
{ "ROLL SUPER", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rates[0], 0, 100, 1, 10 }, 0 },
{ "PITCH SUPER", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rates[1], 0, 100, 1, 10 }, 0 },
{ "YAW SUPER", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rates[2], 0, 100, 1, 10 }, 0 },
{ "RC EXPO", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcExpo8, 0, 100, 1, 10 }, 0 },
{ "RC YAW EXP", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcYawExpo8, 0, 100, 1, 10 }, 0 },
{ "THRPID ATT", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.dynThrPID, 0, 100, 1, 10}, 0 },
{ "TPA BRKPT", OME_UINT16, NULL, &(OSD_UINT16_t){ &rateProfile.tpa_breakpoint, 1000, 2000, 10}, 0 },
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
};
static CMS_Menu cmsx_menuRateProfile = {
.GUARD_text = "MENURATE",
.GUARD_type = OME_MENU,
.onEnter = cmsx_RateProfileOnEnter,
.onExit = cmsx_RateProfileWriteback,
.onGlobalExit = NULL,
.entries = cmsx_menuRateProfileEntries
};
static uint8_t cmsx_dtermSetpointWeight;
static uint8_t cmsx_setpointRelaxRatio;
static uint8_t cmsx_angleStrength;
static uint8_t cmsx_horizonStrength;
static uint8_t cmsx_horizonTransition;
static long cmsx_profileOtherOnEnter(void)
{
profileIndexString[1] = '0' + tmpProfileIndex;
cmsx_dtermSetpointWeight = masterConfig.profile[profileIndex].pidProfile.dtermSetpointWeight;
cmsx_setpointRelaxRatio = masterConfig.profile[profileIndex].pidProfile.setpointRelaxRatio;
cmsx_angleStrength = masterConfig.profile[profileIndex].pidProfile.P8[PIDLEVEL];
cmsx_horizonStrength = masterConfig.profile[profileIndex].pidProfile.I8[PIDLEVEL];
cmsx_horizonTransition = masterConfig.profile[profileIndex].pidProfile.D8[PIDLEVEL];
return 0;
}
static long cmsx_profileOtherOnExit(const OSD_Entry *self)
{
UNUSED(self);
masterConfig.profile[profileIndex].pidProfile.dtermSetpointWeight = cmsx_dtermSetpointWeight;
masterConfig.profile[profileIndex].pidProfile.setpointRelaxRatio = cmsx_setpointRelaxRatio;
masterConfig.profile[profileIndex].pidProfile.P8[PIDLEVEL] = cmsx_angleStrength;
masterConfig.profile[profileIndex].pidProfile.I8[PIDLEVEL] = cmsx_horizonStrength;
masterConfig.profile[profileIndex].pidProfile.D8[PIDLEVEL] = cmsx_horizonTransition;
return 0;
}
static OSD_Entry cmsx_menuProfileOtherEntries[] = {
{ "-- OTHER PP --", OME_Label, NULL, profileIndexString, 0 },
{ "D SETPT WT", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_dtermSetpointWeight, 0, 255, 1, 10 }, 0 },
{ "SETPT TRS", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_setpointRelaxRatio, 0, 100, 1, 10 }, 0 },
{ "ANGLE STR", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_angleStrength, 0, 200, 1 } , 0 },
{ "HORZN STR", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_horizonStrength, 0, 200, 1 } , 0 },
{ "HORZN TRS", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_horizonTransition, 0, 200, 1 } , 0 },
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
};
static CMS_Menu cmsx_menuProfileOther = {
.GUARD_text = "XPROFOTHER",
.GUARD_type = OME_MENU,
.onEnter = cmsx_profileOtherOnEnter,
.onExit = cmsx_profileOtherOnExit,
.onGlobalExit = NULL,
.entries = cmsx_menuProfileOtherEntries,
};
static OSD_Entry cmsx_menuFilterGlobalEntries[] =
{
{ "-- FILTER GLB --", OME_Label, NULL, NULL, 0 },
{ "GYRO LPF", OME_UINT8, NULL, &(OSD_UINT8_t) { &masterConfig.gyro_soft_lpf_hz, 0, 255, 1 }, 0 },
{ "GYRO NF1", OME_UINT16, NULL, &(OSD_UINT16_t) { &masterConfig.gyro_soft_notch_hz_1, 0, 500, 1 }, 0 },
{ "GYRO NF1C", OME_UINT16, NULL, &(OSD_UINT16_t) { &masterConfig.gyro_soft_notch_cutoff_1, 0, 500, 1 }, 0 },
{ "GYRO NF2", OME_UINT16, NULL, &(OSD_UINT16_t) { &masterConfig.gyro_soft_notch_hz_2, 0, 500, 1 }, 0 },
{ "GYRO NF2C", OME_UINT16, NULL, &(OSD_UINT16_t) { &masterConfig.gyro_soft_notch_cutoff_2, 0, 500, 1 }, 0 },
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
};
static CMS_Menu cmsx_menuFilterGlobal = {
.GUARD_text = "XFLTGLB",
.GUARD_type = OME_MENU,
.onEnter = NULL,
.onExit = NULL,
.onGlobalExit = NULL,
.entries = cmsx_menuFilterGlobalEntries,
};
static uint16_t cmsx_dterm_lpf_hz;
static uint16_t cmsx_dterm_notch_hz;
static uint16_t cmsx_dterm_notch_cutoff;
static uint16_t cmsx_yaw_lpf_hz;
static uint16_t cmsx_yaw_p_limit;
static long cmsx_FilterPerProfileRead(void)
{
cmsx_dterm_lpf_hz = masterConfig.profile[profileIndex].pidProfile.dterm_lpf_hz;
cmsx_dterm_notch_hz = masterConfig.profile[profileIndex].pidProfile.dterm_notch_hz;
cmsx_dterm_notch_cutoff = masterConfig.profile[profileIndex].pidProfile.dterm_notch_cutoff;
cmsx_yaw_lpf_hz = masterConfig.profile[profileIndex].pidProfile.yaw_lpf_hz;
cmsx_yaw_p_limit = masterConfig.profile[profileIndex].pidProfile.yaw_p_limit;
return 0;
}
static long cmsx_FilterPerProfileWriteback(const OSD_Entry *self)
{
UNUSED(self);
masterConfig.profile[profileIndex].pidProfile.dterm_lpf_hz = cmsx_dterm_lpf_hz;
masterConfig.profile[profileIndex].pidProfile.dterm_notch_hz = cmsx_dterm_notch_hz;
masterConfig.profile[profileIndex].pidProfile.dterm_notch_cutoff = cmsx_dterm_notch_cutoff;
masterConfig.profile[profileIndex].pidProfile.yaw_lpf_hz = cmsx_yaw_lpf_hz;
masterConfig.profile[profileIndex].pidProfile.yaw_p_limit = cmsx_yaw_p_limit;
return 0;
}
static OSD_Entry cmsx_menuFilterPerProfileEntries[] =
{
{ "-- FILTER PP --", OME_Label, NULL, NULL, 0 },
{ "DTERM LPF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_lpf_hz, 0, 500, 1 }, 0 },
{ "DTERM NF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_notch_hz, 0, 500, 1 }, 0 },
{ "DTERM NFCO", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_notch_cutoff, 0, 500, 1 }, 0 },
{ "YAW LPF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_yaw_lpf_hz, 0, 500, 1 }, 0 },
{ "YAW P LIM", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_yaw_p_limit, 100, 500, 1 }, 0 },
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
};
static CMS_Menu cmsx_menuFilterPerProfile = {
.GUARD_text = "XFLTPP",
.GUARD_type = OME_MENU,
.onEnter = cmsx_FilterPerProfileRead,
.onExit = cmsx_FilterPerProfileWriteback,
.onGlobalExit = NULL,
.entries = cmsx_menuFilterPerProfileEntries,
};
#endif // NOT_YET
static OSD_Entry cmsx_menuImuEntries[] =
{
{ "-- IMU --", OME_Label, NULL, NULL, 0},
// Profile dependent
{"PID PROF", OME_UINT8, cmsx_profileIndexOnChange, &(OSD_UINT8_t){ &tmpProfileIndex, 1, MAX_PROFILE_COUNT, 1}, 0},
{"PID", OME_Submenu, cmsMenuChange, &cmsx_menuPid, 0},
#ifdef NOT_YET
{"OTHER PP", OME_Submenu, cmsMenuChange, &cmsx_menuProfileOther, 0},
{"FILT PP", OME_Submenu, cmsMenuChange, &cmsx_menuFilterPerProfile, 0},
// Profile & rate profile dependent
{"RATE PROF", OME_UINT8, cmsx_rateProfileIndexOnChange, &(OSD_UINT8_t){ &tmpRateProfileIndex, 1, MAX_RATEPROFILES, 1}, 0},
{"RATE", OME_Submenu, cmsMenuChange, &cmsx_menuRateProfile, 0},
// Profile independent
{"FILT GLB", OME_Submenu, cmsMenuChange, &cmsx_menuFilterGlobal, 0},
#endif
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
CMS_Menu cmsx_menuImu = {
.GUARD_text = "XIMU",
.GUARD_type = OME_MENU,
.onEnter = cmsx_menuImu_onEnter,
.onExit = cmsx_menuImu_onExit,
.onGlobalExit = NULL,
.entries = cmsx_menuImuEntries,
};
#endif // CMS

View file

@ -0,0 +1,20 @@
/*
* 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/>.
*/
#pragma once
extern CMS_Menu cmsx_menuImu;

View file

@ -0,0 +1,89 @@
/*
* 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"
#include "build/version.h"
#ifdef CMS
#include "common/axis.h"
#include "io/gimbal.h"
#include "flight/pid.h"
#include "flight/mixer.h"
#include "flight/servos.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
#include "config/feature.h"
#include "cms/cms.h"
#include "cms/cms_types.h"
#include "cms/cms_menu_ledstrip.h"
#ifdef LED_STRIP
static bool featureRead = false;
static uint8_t cmsx_FeatureLedstrip;
static long cmsx_Ledstrip_FeatureRead(void)
{
if (!featureRead) {
cmsx_FeatureLedstrip = feature(FEATURE_LED_STRIP) ? 1 : 0;
featureRead = true;
}
return 0;
}
static long cmsx_Ledstrip_FeatureWriteback(void)
{
if (cmsx_FeatureLedstrip)
featureSet(FEATURE_LED_STRIP);
else
featureClear(FEATURE_LED_STRIP);
return 0;
}
static OSD_Entry cmsx_menuLedstripEntries[] =
{
{ "-- LED STRIP --", OME_Label, NULL, NULL, 0 },
{ "ENABLED", OME_Bool, NULL, &cmsx_FeatureLedstrip, 0 },
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
};
CMS_Menu cmsx_menuLedstrip = {
.GUARD_text = "MENULED",
.GUARD_type = OME_MENU,
.onEnter = cmsx_Ledstrip_FeatureRead,
.onExit = NULL,
.onGlobalExit = cmsx_Ledstrip_FeatureWriteback,
.entries = cmsx_menuLedstripEntries
};
#endif // LED_STRIP
#endif // CMS

View file

@ -0,0 +1,20 @@
/*
* 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/>.
*/
#pragma once
extern CMS_Menu cmsx_menuLedstrip;

View file

@ -0,0 +1,111 @@
/*
* 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"
#include "build/version.h"
#ifdef CMS
#include "common/axis.h"
#include "io/gimbal.h"
#include "flight/pid.h"
#include "flight/mixer.h"
#include "flight/servos.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
#include "config/feature.h"
#include "cms/cms.h"
#include "cms/cms_types.h"
#include "cms/cms_menu_ledstrip.h"
//
// Misc
//
static long cmsx_menuRcConfirmBack(const OSD_Entry *self)
{
if (self && self->type == OME_Back)
return 0;
else
return -1;
}
//
// RC preview
//
static OSD_Entry cmsx_menuRcEntries[] =
{
{ "-- RC PREV --", OME_Label, NULL, NULL, 0},
{ "ROLL", OME_INT16, NULL, &(OSD_INT16_t){ &rcData[ROLL], 1, 2500, 0 }, DYNAMIC },
{ "PITCH", OME_INT16, NULL, &(OSD_INT16_t){ &rcData[PITCH], 1, 2500, 0 }, DYNAMIC },
{ "THR", OME_INT16, NULL, &(OSD_INT16_t){ &rcData[THROTTLE], 1, 2500, 0 }, DYNAMIC },
{ "YAW", OME_INT16, NULL, &(OSD_INT16_t){ &rcData[YAW], 1, 2500, 0 }, DYNAMIC },
{ "AUX1", OME_INT16, NULL, &(OSD_INT16_t){ &rcData[AUX1], 1, 2500, 0 }, DYNAMIC },
{ "AUX2", OME_INT16, NULL, &(OSD_INT16_t){ &rcData[AUX2], 1, 2500, 0 }, DYNAMIC },
{ "AUX3", OME_INT16, NULL, &(OSD_INT16_t){ &rcData[AUX3], 1, 2500, 0 }, DYNAMIC },
{ "AUX4", OME_INT16, NULL, &(OSD_INT16_t){ &rcData[AUX4], 1, 2500, 0 }, DYNAMIC },
{ "BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
CMS_Menu cmsx_menuRcPreview = {
.GUARD_text = "XRCPREV",
.GUARD_type = OME_MENU,
.onEnter = NULL,
.onExit = cmsx_menuRcConfirmBack,
.onGlobalExit = NULL,
.entries = cmsx_menuRcEntries
};
static OSD_Entry menuMiscEntries[]=
{
{ "-- MISC --", OME_Label, NULL, NULL, 0 },
{ "MIN THR", OME_UINT16, NULL, &(OSD_UINT16_t){ &masterConfig.motorConfig.minthrottle, 1000, 2000, 1 }, 0 },
{ "VBAT SCALE", OME_UINT8, NULL, &(OSD_UINT8_t) { &masterConfig.batteryConfig.vbatscale, 1, 250, 1 }, 0 },
{ "VBAT CLMAX", OME_UINT8, NULL, &(OSD_UINT8_t) { &masterConfig.batteryConfig.vbatmaxcellvoltage, 10, 50, 1 }, 0 },
{ "RC PREV", OME_Submenu, cmsMenuChange, &cmsx_menuRcPreview, 0},
{ "BACK", OME_Back, NULL, NULL, 0},
{ NULL, OME_END, NULL, NULL, 0}
};
CMS_Menu cmsx_menuMisc = {
.GUARD_text = "XMISC",
.GUARD_type = OME_MENU,
.onEnter = NULL,
.onExit = NULL,
.onGlobalExit = NULL,
.entries = menuMiscEntries
};
#endif // CMS

View file

@ -0,0 +1,20 @@
/*
* 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/>.
*/
#pragma once
extern CMS_Menu cmsx_menuMisc;

121
src/main/cms/cms_menu_osd.c Normal file
View file

@ -0,0 +1,121 @@
/*
* 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 <ctype.h>
#include "platform.h"
#include "build/version.h"
#include "cms/cms.h"
#include "cms/cms_types.h"
#include "cms/cms_menu_osd.h"
#include "common/axis.h"
#include "io/gimbal.h"
#include "flight/pid.h"
#include "flight/mixer.h"
#include "flight/servos.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
#include "config/feature.h"
#if defined(OSD) && defined(CMS)
OSD_UINT8_t entryAlarmRssi = {&masterConfig.osdProfile.rssi_alarm, 5, 90, 5};
OSD_UINT16_t entryAlarmCapacity = {&masterConfig.osdProfile.cap_alarm, 50, 30000, 50};
OSD_UINT16_t enryAlarmFlyTime = {&masterConfig.osdProfile.time_alarm, 1, 200, 1};
OSD_UINT16_t entryAlarmAltitude = {&masterConfig.osdProfile.alt_alarm, 1, 200, 1};
OSD_Entry cmsx_menuAlarmsEntries[] =
{
{"--- ALARMS ---", OME_Label, NULL, NULL, 0},
{"RSSI", OME_UINT8, NULL, &entryAlarmRssi, 0},
{"MAIN BAT", OME_UINT16, NULL, &entryAlarmCapacity, 0},
{"FLY TIME", OME_UINT16, NULL, &enryAlarmFlyTime, 0},
{"MAX ALT", OME_UINT16, NULL, &entryAlarmAltitude, 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
CMS_Menu cmsx_menuAlarms = {
.GUARD_text = "MENUALARMS",
.GUARD_type = OME_MENU,
.onEnter = NULL,
.onExit = NULL,
.onGlobalExit = NULL,
.entries = cmsx_menuAlarmsEntries,
};
OSD_Entry menuOsdActiveElemsEntries[] =
{
{"--- ACTIV ELEM ---", OME_Label, NULL, NULL, 0},
{"RSSI", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE], 0},
{"MAIN BATTERY", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE], 0},
{"HORIZON", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON], 0},
{"HORIZON SIDEBARS", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_HORIZON_SIDEBARS], 0},
{"UPTIME", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_ONTIME], 0},
{"FLY TIME", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_FLYTIME], 0},
{"FLY MODE", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_FLYMODE], 0},
{"NAME", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_CRAFT_NAME], 0},
{"THROTTLE", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS], 0},
#ifdef VTX
{"VTX CHAN", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_VTX_CHANNEL]},
#endif // VTX
{"CURRENT (A)", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_CURRENT_DRAW], 0},
{"USED MAH", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_MAH_DRAWN], 0},
#ifdef GPS
{"GPS SPEED", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_GPS_SPEED], 0},
{"GPS SATS.", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_GPS_SATS], 0},
#endif // GPS
{"ALTITUDE", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_ALTITUDE], 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
CMS_Menu menuOsdActiveElems = {
.GUARD_text = "MENUOSDACT",
.GUARD_type = OME_MENU,
.onEnter = NULL,
.onExit = NULL,
.onGlobalExit = NULL,
.entries = menuOsdActiveElemsEntries
};
OSD_Entry cmsx_menuOsdLayoutEntries[] =
{
{"---SCREEN LAYOUT---", OME_Label, NULL, NULL, 0},
{"ACTIVE ELEM", OME_Submenu, cmsMenuChange, &menuOsdActiveElems, 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
CMS_Menu cmsx_menuOsdLayout = {
.GUARD_text = "MENULAYOUT",
.GUARD_type = OME_MENU,
.onEnter = NULL,
.onExit = NULL,
.onGlobalExit = NULL,
.entries = cmsx_menuOsdLayoutEntries
};
#endif // CMS

View file

@ -0,0 +1,21 @@
/*
* 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/>.
*/
#pragma once
extern CMS_Menu cmsx_menuAlarms;
extern CMS_Menu cmsx_menuOsdLayout;

146
src/main/cms/cms_menu_vtx.c Normal file
View file

@ -0,0 +1,146 @@
/*
* 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 <ctype.h>
#include "platform.h"
#include "build/version.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"
#include "config/feature.h"
#ifdef CMS
#if defined(VTX) || defined(USE_RTC6705)
static bool featureRead = false;
static uint8_t cmsx_featureVtx = 0, cmsx_vtxBand, cmsx_vtxChannel;
static long cmsx_Vtx_FeatureRead(void)
{
if (!featureRead) {
cmsx_featureVtx = feature(FEATURE_VTX) ? 1 : 0;
featureRead = true;
}
return 0;
}
static long cmsx_Vtx_FeatureWriteback(void)
{
if (cmsx_featureVtx)
featureSet(FEATURE_VTX);
else
featureClear(FEATURE_VTX);
return 0;
}
static const char * const vtxBandNames[] = {
"BOSCAM A",
"BOSCAM B",
"BOSCAM E",
"FATSHARK",
"RACEBAND",
};
static OSD_TAB_t entryVtxBand = {&cmsx_vtxBand,4,&vtxBandNames[0]};
static OSD_UINT8_t entryVtxChannel = {&cmsx_vtxChannel, 1, 8, 1};
static void cmsx_Vtx_ConfigRead(void)
{
#ifdef VTX
cmsx_vtxBand = masterConfig.vtx_band;
cmsx_vtxChannel = masterConfig.vtx_channel + 1;
#endif // VTX
#ifdef USE_RTC6705
cmsx_vtxBand = masterConfig.vtx_channel / 8;
cmsx_vtxChannel = masterConfig.vtx_channel % 8 + 1;
#endif // USE_RTC6705
}
static void cmsx_Vtx_ConfigWriteback(void)
{
#ifdef VTX
masterConfig.vtx_band = cmsx_vtxBand;
masterConfig.vtx_channel = cmsx_vtxChannel - 1;
#endif // VTX
#ifdef USE_RTC6705
masterConfig.vtx_channel = cmsx_vtxBand * 8 + cmsx_vtxChannel - 1;
#endif // USE_RTC6705
}
static long cmsx_Vtx_onEnter(void)
{
cmsx_Vtx_FeatureRead();
cmsx_Vtx_ConfigRead();
return 0;
}
static long cmsx_Vtx_onExit(const OSD_Entry *self)
{
UNUSED(self);
cmsx_Vtx_ConfigWriteback();
return 0;
}
#ifdef VTX
static OSD_UINT8_t entryVtxMode = {&masterConfig.vtx_mode, 0, 2, 1};
static OSD_UINT16_t entryVtxMhz = {&masterConfig.vtx_mhz, 5600, 5950, 1};
#endif // VTX
static OSD_Entry cmsx_menuVtxEntries[] =
{
{"--- VTX ---", OME_Label, NULL, NULL, 0},
{"ENABLED", OME_Bool, NULL, &cmsx_featureVtx, 0},
#ifdef VTX
{"VTX MODE", OME_UINT8, NULL, &entryVtxMode, 0},
{"VTX MHZ", OME_UINT16, NULL, &entryVtxMhz, 0},
#endif // VTX
{"BAND", OME_TAB, NULL, &entryVtxBand, 0},
{"CHANNEL", OME_UINT8, NULL, &entryVtxChannel, 0},
#ifdef USE_RTC6705
{"LOW POWER", OME_Bool, NULL, &masterConfig.vtx_power, 0},
#endif // USE_RTC6705
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
CMS_Menu cmsx_menuVtx = {
.GUARD_text = "MENUVTX",
.GUARD_type = OME_MENU,
.onEnter = cmsx_Vtx_onEnter,
.onExit= cmsx_Vtx_onExit,
.onGlobalExit = cmsx_Vtx_FeatureWriteback,
.entries = cmsx_menuVtxEntries
};
#endif // VTX || USE_RTC6705
#endif // CMS

View file

@ -0,0 +1,20 @@
/*
* 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/>.
*/
#pragma once
extern CMS_Menu cmsx_menuVtx;

155
src/main/cms/cms_types.h Normal file
View file

@ -0,0 +1,155 @@
/*
* 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/>.
*/
//
// Menu element types
// XXX Upon separation, all OME would be renamed to CME_ or similar.
//
#pragma once
//type of elements
typedef enum
{
OME_Label,
OME_Back,
OME_OSD_Exit,
OME_Submenu,
OME_Funcall,
OME_Bool,
OME_INT8,
OME_UINT8,
OME_UINT16,
OME_INT16,
OME_String,
OME_FLOAT, //only up to 255 value and cant be 2.55 or 25.5, just for PID's
//wlasciwosci elementow
#ifdef OSD
OME_VISIBLE,
#endif
OME_TAB,
OME_END,
// Debug aid
OME_MENU,
OME_MAX = OME_MENU
} OSD_MenuElement;
typedef long (*CMSEntryFuncPtr)(displayPort_t *displayPort, const void *ptr);
typedef struct
{
const char *text;
const OSD_MenuElement type;
const CMSEntryFuncPtr func;
void *data;
uint8_t flags;
} OSD_Entry;
// Bits in flags
#define PRINT_VALUE 0x01 // Value has been changed, need to redraw
#define PRINT_LABEL 0x02 // Text label should be printed
#define DYNAMIC 0x04 // Value should be updated dynamically
#define IS_PRINTVALUE(p) ((p)->flags & PRINT_VALUE)
#define SET_PRINTVALUE(p) { (p)->flags |= PRINT_VALUE; }
#define CLR_PRINTVALUE(p) { (p)->flags &= ~PRINT_VALUE; }
#define IS_PRINTLABEL(p) ((p)->flags & PRINT_LABEL)
#define SET_PRINTLABEL(p) { (p)->flags |= PRINT_LABEL; }
#define CLR_PRINTLABEL(p) { (p)->flags &= ~PRINT_LABEL; }
#define IS_DYNAMIC(p) ((p)->flags & DYNAMIC)
typedef long (*CMSMenuFuncPtr)(void);
/*
onExit function is called with self:
(1) Pointer to an OSD_Entry when cmsMenuBack() was called.
Point to an OSD_Entry with type == OME_Back if BACK was selected.
(2) NULL if called from menu exit (forced exit at top level).
*/
typedef long (*CMSMenuOnExitPtr)(const OSD_Entry *self);
typedef struct
{
// These two are debug aids for menu content creators.
const char *GUARD_text;
const OSD_MenuElement GUARD_type;
const CMSMenuFuncPtr onEnter;
const CMSMenuOnExitPtr onExit;
const CMSMenuFuncPtr onGlobalExit;
OSD_Entry *entries;
} CMS_Menu;
typedef struct
{
uint8_t *val;
uint8_t min;
uint8_t max;
uint8_t step;
} OSD_UINT8_t;
typedef struct
{
int8_t *val;
int8_t min;
int8_t max;
int8_t step;
} OSD_INT8_t;
typedef struct
{
int16_t *val;
int16_t min;
int16_t max;
int16_t step;
} OSD_INT16_t;
typedef struct
{
uint16_t *val;
uint16_t min;
uint16_t max;
uint16_t step;
} OSD_UINT16_t;
typedef struct
{
uint8_t *val;
uint8_t min;
uint8_t max;
uint8_t step;
uint16_t multipler;
} OSD_FLOAT_t;
typedef struct
{
uint8_t *val;
uint8_t max;
const char * const *names;
} OSD_TAB_t;
typedef struct
{
char *val;
} OSD_String_t;

View file

@ -52,6 +52,7 @@
#include "fc/rc_curves.h" #include "fc/rc_curves.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/osd.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "rx/rx_spi.h" #include "rx/rx_spi.h"
@ -464,6 +465,11 @@ static void resetConf(void)
featureSet(DEFAULT_FEATURES); featureSet(DEFAULT_FEATURES);
#endif #endif
#ifdef OSD
featureSet(FEATURE_OSD);
osdResetConfig(&masterConfig.osdProfile);
#endif
#ifdef BOARD_HAS_VOLTAGE_DIVIDER #ifdef BOARD_HAS_VOLTAGE_DIVIDER
// only enable the VBAT feature by default if the board has a voltage divider otherwise // only enable the VBAT feature by default if the board has a voltage divider otherwise
// the user may see incorrect readings and unexpected issues with pin mappings may occur. // the user may see incorrect readings and unexpected issues with pin mappings may occur.

View file

@ -27,6 +27,7 @@
#endif #endif
#define MAX_CONTROL_RATE_PROFILE_COUNT 3 #define MAX_CONTROL_RATE_PROFILE_COUNT 3
#define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500 #define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500
#define MAX_NAME_LENGTH 16
#define ACC_TASK_FREQUENCY_DEFAULT 500 #define ACC_TASK_FREQUENCY_DEFAULT 500
#define ACC_TASK_FREQUENCY_MIN 100 #define ACC_TASK_FREQUENCY_MIN 100
@ -73,6 +74,7 @@ typedef enum {
FEATURE_SOFTSPI = 1 << 26, FEATURE_SOFTSPI = 1 << 26,
FEATURE_PWM_SERVO_DRIVER = 1 << 27, FEATURE_PWM_SERVO_DRIVER = 1 << 27,
FEATURE_PWM_OUTPUT_ENABLE = 1 << 28, FEATURE_PWM_OUTPUT_ENABLE = 1 << 28,
FEATURE_OSD = 1 << 29,
} features_e; } features_e;
typedef enum { typedef enum {

View file

@ -34,6 +34,7 @@
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/osd.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"
#include "io/motors.h" #include "io/motors.h"
#include "io/serial.h" #include "io/serial.h"
@ -154,6 +155,10 @@ typedef struct master_s {
uint8_t ledstrip_visual_beeper; // suppress LEDLOW mode if beeper is on uint8_t ledstrip_visual_beeper; // suppress LEDLOW mode if beeper is on
#endif #endif
#ifdef OSD
osd_profile_t osdProfile;
#endif
profile_t profile[MAX_PROFILE_COUNT]; profile_t profile[MAX_PROFILE_COUNT];
uint8_t current_profile_index; uint8_t current_profile_index;
controlRateConfig_t controlRateProfiles[MAX_CONTROL_RATE_PROFILE_COUNT]; controlRateConfig_t controlRateProfiles[MAX_CONTROL_RATE_PROFILE_COUNT];
@ -167,6 +172,8 @@ typedef struct master_s {
uint32_t beeper_off_flags; uint32_t beeper_off_flags;
uint32_t preferred_beeper_off_flags; uint32_t preferred_beeper_off_flags;
char name[MAX_NAME_LENGTH + 1];
uint8_t magic_ef; // magic number, should be 0xEF uint8_t magic_ef; // magic number, should be 0xEF
uint8_t chk; // XOR checksum uint8_t chk; // XOR checksum
} master_t; } master_t;

View file

@ -0,0 +1,72 @@
/*
* 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 "platform.h"
#include "common/utils.h"
#include "display.h"
void displayClear(displayPort_t *instance)
{
instance->vTable->clear(instance);
instance->cleared = true;
instance->cursorRow = -1;
}
void displayGrab(displayPort_t *instance)
{
instance->vTable->grab(instance);
instance->vTable->clear(instance);
instance->isGrabbed = true;
}
void displayRelease(displayPort_t *instance)
{
instance->vTable->release(instance);
instance->isGrabbed = false;
}
bool displayIsGrabbed(const displayPort_t *instance)
{
// can be called before initialised
return (instance && instance->isGrabbed);
}
int displayWrite(displayPort_t *instance, uint8_t x, uint8_t y, const char *s)
{
return instance->vTable->write(instance, x, y, s);
}
void displayHeartbeat(displayPort_t *instance)
{
instance->vTable->heartbeat(instance);
}
void displayResync(displayPort_t *instance)
{
instance->vTable->resync(instance);
}
uint16_t displayTxBytesFree(const displayPort_t *instance)
{
return instance->vTable->txBytesFree(instance);
}

View file

@ -0,0 +1,49 @@
/*
* 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/>.
*/
#pragma once
struct displayPortVTable_s;
typedef struct displayPort_s {
const struct displayPortVTable_s *vTable;
uint8_t rows;
uint8_t cols;
// CMS state
bool cleared;
int8_t cursorRow;
bool isGrabbed;
} displayPort_t;
typedef struct displayPortVTable_s {
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);
void (*resync)(displayPort_t *displayPort);
uint32_t (*txBytesFree)(const displayPort_t *displayPort);
} displayPortVTable_t;
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);
void displayResync(displayPort_t *instance);
uint16_t displayTxBytesFree(const displayPort_t *instance);

429
src/main/drivers/max7456.c Normal file
View file

@ -0,0 +1,429 @@
/*
* 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 <stdio.h>
#include <stdlib.h>
#include <string.h>
#include "platform.h"
#ifdef USE_MAX7456
#include "common/printf.h"
#include "drivers/bus_spi.h"
#include "drivers/light_led.h"
#include "drivers/io.h"
#include "drivers/system.h"
#include "drivers/nvic.h"
#include "drivers/dma.h"
#include "max7456.h"
#include "max7456_symbols.h"
//on shared SPI buss we want to change clock for OSD chip and restore for other devices
#ifdef MAX7456_SPI_CLK
#define ENABLE_MAX7456 {spiSetDivisor(MAX7456_SPI_INSTANCE, MAX7456_SPI_CLK);IOLo(max7456CsPin);}
#else
#define ENABLE_MAX7456 IOLo(max7456CsPin)
#endif
#ifdef MAX7456_RESTORE_CLK
#define DISABLE_MAX7456 {IOHi(max7456CsPin);spiSetDivisor(MAX7456_SPI_INSTANCE, MAX7456_RESTORE_CLK);}
#else
#define DISABLE_MAX7456 IOHi(max7456CsPin)
#endif
uint16_t maxScreenSize = VIDEO_BUFFER_CHARS_PAL;
// we write everything in screenBuffer and then comapre
// screenBuffer with shadowBuffer to upgrade only changed chars
// this solution is faster then redraw all screen
static uint8_t screenBuffer[VIDEO_BUFFER_CHARS_PAL+40]; //for faster writes we use memcpy so we need some space to don't overwrite buffer
static uint8_t shadowBuffer[VIDEO_BUFFER_CHARS_PAL];
//max chars to update in one idle
#define MAX_CHARS2UPDATE 100
#ifdef MAX7456_DMA_CHANNEL_TX
volatile bool dmaTransactionInProgress = false;
#endif
static uint8_t spiBuff[MAX_CHARS2UPDATE*6];
static uint8_t videoSignalCfg = 0;
static uint8_t videoSignalReg = VIDEO_MODE_PAL | OSD_ENABLE; //PAL by default
static bool max7456Lock = false;
static bool fontIsLoading = false;
static IO_t max7456CsPin = IO_NONE;
static uint8_t max7456Send(uint8_t add, uint8_t data)
{
spiTransferByte(MAX7456_SPI_INSTANCE, add);
return spiTransferByte(MAX7456_SPI_INSTANCE, data);
}
#ifdef MAX7456_DMA_CHANNEL_TX
static void max7456SendDma(void* tx_buffer, void* rx_buffer, uint16_t buffer_size)
{
DMA_InitTypeDef DMA_InitStructure;
#ifdef MAX7456_DMA_CHANNEL_RX
static uint16_t dummy[] = {0xffff};
#else
UNUSED(rx_buffer);
#endif
while (dmaTransactionInProgress); // Wait for prev DMA transaction
DMA_DeInit(MAX7456_DMA_CHANNEL_TX);
#ifdef MAX7456_DMA_CHANNEL_RX
DMA_DeInit(MAX7456_DMA_CHANNEL_RX);
#endif
// Common to both channels
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)(&(MAX7456_SPI_INSTANCE->DR));
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
DMA_InitStructure.DMA_BufferSize = buffer_size;
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
DMA_InitStructure.DMA_Priority = DMA_Priority_Low;
#ifdef MAX7456_DMA_CHANNEL_RX
// Rx Channel
#ifdef STM32F4
DMA_InitStructure.DMA_Memory0BaseAddr = rx_buffer ? (uint32_t)rx_buffer : (uint32_t)(dummy);
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory;
#else
DMA_InitStructure.DMA_MemoryBaseAddr = rx_buffer ? (uint32_t)rx_buffer : (uint32_t)(dummy);
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
#endif
DMA_InitStructure.DMA_MemoryInc = rx_buffer ? DMA_MemoryInc_Enable : DMA_MemoryInc_Disable;
DMA_Init(MAX7456_DMA_CHANNEL_RX, &DMA_InitStructure);
DMA_Cmd(MAX7456_DMA_CHANNEL_RX, ENABLE);
#endif
// Tx channel
#ifdef STM32F4
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)tx_buffer; //max7456_screen;
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
#else
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)tx_buffer; //max7456_screen;
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
#endif
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
DMA_Init(MAX7456_DMA_CHANNEL_TX, &DMA_InitStructure);
DMA_Cmd(MAX7456_DMA_CHANNEL_TX, ENABLE);
#ifdef MAX7456_DMA_CHANNEL_RX
DMA_ITConfig(MAX7456_DMA_CHANNEL_RX, DMA_IT_TC, ENABLE);
#else
DMA_ITConfig(MAX7456_DMA_CHANNEL_TX, DMA_IT_TC, ENABLE);
#endif
// Enable SPI TX/RX request
ENABLE_MAX7456;
dmaTransactionInProgress = true;
SPI_I2S_DMACmd(MAX7456_SPI_INSTANCE,
#ifdef MAX7456_DMA_CHANNEL_RX
SPI_I2S_DMAReq_Rx |
#endif
SPI_I2S_DMAReq_Tx, ENABLE);
}
void max7456_dma_irq_handler(dmaChannelDescriptor_t* descriptor)
{
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
#ifdef MAX7456_DMA_CHANNEL_RX
DMA_Cmd(MAX7456_DMA_CHANNEL_RX, DISABLE);
#endif
// make sure spi dmd transfer is complete
while (SPI_I2S_GetFlagStatus (MAX7456_SPI_INSTANCE, SPI_I2S_FLAG_TXE) == RESET) {};
while (SPI_I2S_GetFlagStatus (MAX7456_SPI_INSTANCE, SPI_I2S_FLAG_BSY) == SET) {};
//Empty RX buffer. RX DMA takes care of it if enabled
//this should be done after transmission finish!!!
while (SPI_I2S_GetFlagStatus(MAX7456_SPI_INSTANCE, SPI_I2S_FLAG_RXNE) == SET) {
MAX7456_SPI_INSTANCE->DR;
}
DMA_Cmd(MAX7456_DMA_CHANNEL_TX, DISABLE);
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
SPI_I2S_DMACmd(MAX7456_SPI_INSTANCE,
#ifdef MAX7456_DMA_CHANNEL_RX
SPI_I2S_DMAReq_Rx |
#endif
SPI_I2S_DMAReq_Tx, DISABLE);
DISABLE_MAX7456;
dmaTransactionInProgress = false;
}
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_HTIF)) {
DMA_CLEAR_FLAG(descriptor, DMA_IT_HTIF);
}
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TEIF)) {
DMA_CLEAR_FLAG(descriptor, DMA_IT_TEIF);
}
}
#endif
uint8_t max7456GetRowsCount(void)
{
if (videoSignalReg & VIDEO_MODE_PAL)
return VIDEO_LINES_PAL;
return VIDEO_LINES_NTSC;
}
//because MAX7456 need some time to detect video system etc. we need to wait for a while to initialize it at startup
//and in case of restart we need to reinitialize chip
void max7456ReInit(void)
{
uint8_t maxScreenRows;
uint8_t srdata = 0;
uint16_t x;
static bool firstInit = true;
//do not init MAX before camera power up correctly
if (millis() < 1500)
return;
ENABLE_MAX7456;
switch(videoSignalCfg) {
case PAL:
videoSignalReg = VIDEO_MODE_PAL | OSD_ENABLE;
break;
case NTSC:
videoSignalReg = VIDEO_MODE_NTSC | OSD_ENABLE;
break;
default:
srdata = max7456Send(MAX7456ADD_STAT, 0x00);
if ((0x02 & srdata) == 0x02)
videoSignalReg = VIDEO_MODE_NTSC | OSD_ENABLE;
}
if (videoSignalReg & VIDEO_MODE_PAL) { //PAL
maxScreenSize = VIDEO_BUFFER_CHARS_PAL;
maxScreenRows = VIDEO_LINES_PAL;
} else { // NTSC
maxScreenSize = VIDEO_BUFFER_CHARS_NTSC;
maxScreenRows = VIDEO_LINES_NTSC;
}
// set all rows to same charactor black/white level
for(x = 0; x < maxScreenRows; x++) {
max7456Send(MAX7456ADD_RB0 + x, BWBRIGHTNESS);
}
// make sure the Max7456 is enabled
max7456Send(VM0_REG, videoSignalReg);
max7456Send(DMM_REG, CLEAR_DISPLAY);
DISABLE_MAX7456;
//clear shadow to force redraw all screen in non-dma mode
memset(shadowBuffer, 0, maxScreenSize);
if (firstInit)
{
max7456RefreshAll();
firstInit = false;
}
}
//here we init only CS and try to init MAX for first time
void max7456Init(uint8_t video_system)
{
#ifdef MAX7456_SPI_CS_PIN
max7456CsPin = IOGetByTag(IO_TAG(MAX7456_SPI_CS_PIN));
#endif
IOInit(max7456CsPin, OWNER_OSD, RESOURCE_SPI_CS, 0);
IOConfigGPIO(max7456CsPin, SPI_IO_CS_CFG);
spiSetDivisor(MAX7456_SPI_INSTANCE, SPI_CLOCK_STANDARD);
// force soft reset on Max7456
ENABLE_MAX7456;
max7456Send(VM0_REG, MAX7456_RESET);
DISABLE_MAX7456;
videoSignalCfg = video_system;
#ifdef MAX7456_DMA_CHANNEL_TX
dmaSetHandler(MAX7456_DMA_IRQ_HANDLER_ID, max7456_dma_irq_handler, NVIC_PRIO_MAX7456_DMA, 0);
#endif
//real init will be made letter when driver idle detect
}
//just fill with spaces with some tricks
void max7456ClearScreen(void)
{
uint16_t x;
uint32_t *p = (uint32_t*)&screenBuffer[0];
for (x = 0; x < VIDEO_BUFFER_CHARS_PAL/4; x++)
p[x] = 0x20202020;
}
uint8_t* max7456GetScreenBuffer(void) {
return screenBuffer;
}
void max7456WriteChar(uint8_t x, uint8_t y, uint8_t c)
{
screenBuffer[y*30+x] = c;
}
void max7456Write(uint8_t x, uint8_t y, const char *buff)
{
uint8_t i = 0;
for (i = 0; *(buff+i); i++)
if (x+i < 30) //do not write over screen
screenBuffer[y*30+x+i] = *(buff+i);
}
#ifdef MAX7456_DMA_CHANNEL_TX
bool max7456DmaInProgres(void)
{
return dmaTransactionInProgress;
}
#endif
void max7456DrawScreen(void)
{
uint8_t check;
static uint16_t pos = 0;
int k = 0, buff_len=0;
if (!max7456Lock && !fontIsLoading) {
//-----------------detect MAX7456 fail, or initialize it at startup when it is ready--------
max7456Lock = true;
ENABLE_MAX7456;
check = max7456Send(VM0_REG | 0x80, 0x00);
DISABLE_MAX7456;
if ( check != videoSignalReg)
max7456ReInit();
//------------ end of (re)init-------------------------------------
for (k=0; k< MAX_CHARS2UPDATE; k++) {
if (screenBuffer[pos] != shadowBuffer[pos]) {
spiBuff[buff_len++] = MAX7456ADD_DMAH;
spiBuff[buff_len++] = pos >> 8;
spiBuff[buff_len++] = MAX7456ADD_DMAL;
spiBuff[buff_len++] = pos & 0xff;
spiBuff[buff_len++] = MAX7456ADD_DMDI;
spiBuff[buff_len++] = screenBuffer[pos];
shadowBuffer[pos] = screenBuffer[pos];
k++;
}
if (++pos >= maxScreenSize) {
pos = 0;
break;
}
}
if (buff_len) {
#ifdef MAX7456_DMA_CHANNEL_TX
if (buff_len > 0)
max7456SendDma(spiBuff, NULL, buff_len);
#else
ENABLE_MAX7456;
for (k=0; k < buff_len; k++)
spiTransferByte(MAX7456_SPI_INSTANCE, spiBuff[k]);
DISABLE_MAX7456;
#endif // MAX7456_DMA_CHANNEL_TX
}
max7456Lock = false;
}
}
// this funcktion refresh all and should not be used when copter is armed
void max7456RefreshAll(void)
{
if (!max7456Lock) {
#ifdef MAX7456_DMA_CHANNEL_TX
while (dmaTransactionInProgress);
#endif
uint16_t xx;
max7456Lock = true;
ENABLE_MAX7456;
max7456Send(MAX7456ADD_DMAH, 0);
max7456Send(MAX7456ADD_DMAL, 0);
max7456Send(MAX7456ADD_DMM, 1);
for (xx = 0; xx < maxScreenSize; ++xx)
{
max7456Send(MAX7456ADD_DMDI, screenBuffer[xx]);
shadowBuffer[xx] = screenBuffer[xx];
}
max7456Send(MAX7456ADD_DMDI, 0xFF);
max7456Send(MAX7456ADD_DMM, 0);
DISABLE_MAX7456;
max7456Lock = false;
}
}
void max7456WriteNvm(uint8_t char_address, const uint8_t *font_data)
{
uint8_t x;
#ifdef MAX7456_DMA_CHANNEL_TX
while (dmaTransactionInProgress);
#endif
while (max7456Lock);
max7456Lock = true;
ENABLE_MAX7456;
// disable display
fontIsLoading = true;
max7456Send(VM0_REG, 0);
max7456Send(MAX7456ADD_CMAH, char_address); // set start address high
for(x = 0; x < 54; x++) {
max7456Send(MAX7456ADD_CMAL, x); //set start address low
max7456Send(MAX7456ADD_CMDI, font_data[x]);
#ifdef LED0_TOGGLE
LED0_TOGGLE;
#else
LED1_TOGGLE;
#endif
}
// transfer 54 bytes from shadow ram to NVM
max7456Send(MAX7456ADD_CMM, WRITE_NVR);
// wait until bit 5 in the status register returns to 0 (12ms)
while ((max7456Send(MAX7456ADD_STAT, 0x00) & STATUS_REG_NVR_BUSY) != 0x00);
DISABLE_MAX7456;
max7456Lock = false;
}
#endif

159
src/main/drivers/max7456.h Normal file
View file

@ -0,0 +1,159 @@
/*
* 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/>.
*/
#pragma once
#ifndef WHITEBRIGHTNESS
#define WHITEBRIGHTNESS 0x01
#endif
#ifndef BLACKBRIGHTNESS
#define BLACKBRIGHTNESS 0x00
#endif
#define BWBRIGHTNESS ((BLACKBRIGHTNESS << 2) | WHITEBRIGHTNESS)
//MAX7456 opcodes
#define DMM_REG 0x04
#define DMAH_REG 0x05
#define DMAL_REG 0x06
#define DMDI_REG 0x07
#define VM0_REG 0x00
#define VM1_REG 0x01
// video mode register 0 bits
#define VIDEO_BUFFER_DISABLE 0x01
#define MAX7456_RESET 0x02
#define VERTICAL_SYNC_NEXT_VSYNC 0x04
#define OSD_ENABLE 0x08
#define SYNC_MODE_AUTO 0x00
#define SYNC_MODE_INTERNAL 0x30
#define SYNC_MODE_EXTERNAL 0x20
#define VIDEO_MODE_PAL 0x40
#define VIDEO_MODE_NTSC 0x00
// video mode register 1 bits
// duty cycle is on_off
#define BLINK_DUTY_CYCLE_50_50 0x00
#define BLINK_DUTY_CYCLE_33_66 0x01
#define BLINK_DUTY_CYCLE_25_75 0x02
#define BLINK_DUTY_CYCLE_75_25 0x03
// blinking time
#define BLINK_TIME_0 0x00
#define BLINK_TIME_1 0x04
#define BLINK_TIME_2 0x08
#define BLINK_TIME_3 0x0C
// background mode brightness (percent)
#define BACKGROUND_BRIGHTNESS_0 0x00
#define BACKGROUND_BRIGHTNESS_7 0x01
#define BACKGROUND_BRIGHTNESS_14 0x02
#define BACKGROUND_BRIGHTNESS_21 0x03
#define BACKGROUND_BRIGHTNESS_28 0x04
#define BACKGROUND_BRIGHTNESS_35 0x05
#define BACKGROUND_BRIGHTNESS_42 0x06
#define BACKGROUND_BRIGHTNESS_49 0x07
#define BACKGROUND_MODE_GRAY 0x40
//MAX7456 commands
#define CLEAR_DISPLAY 0x04
#define CLEAR_DISPLAY_VERT 0x06
#define END_STRING 0xff
#define MAX7456ADD_VM0 0x00 //0b0011100// 00 // 00 ,0011100
#define MAX7456ADD_VM1 0x01
#define MAX7456ADD_HOS 0x02
#define MAX7456ADD_VOS 0x03
#define MAX7456ADD_DMM 0x04
#define MAX7456ADD_DMAH 0x05
#define MAX7456ADD_DMAL 0x06
#define MAX7456ADD_DMDI 0x07
#define MAX7456ADD_CMM 0x08
#define MAX7456ADD_CMAH 0x09
#define MAX7456ADD_CMAL 0x0a
#define MAX7456ADD_CMDI 0x0b
#define MAX7456ADD_OSDM 0x0c
#define MAX7456ADD_RB0 0x10
#define MAX7456ADD_RB1 0x11
#define MAX7456ADD_RB2 0x12
#define MAX7456ADD_RB3 0x13
#define MAX7456ADD_RB4 0x14
#define MAX7456ADD_RB5 0x15
#define MAX7456ADD_RB6 0x16
#define MAX7456ADD_RB7 0x17
#define MAX7456ADD_RB8 0x18
#define MAX7456ADD_RB9 0x19
#define MAX7456ADD_RB10 0x1a
#define MAX7456ADD_RB11 0x1b
#define MAX7456ADD_RB12 0x1c
#define MAX7456ADD_RB13 0x1d
#define MAX7456ADD_RB14 0x1e
#define MAX7456ADD_RB15 0x1f
#define MAX7456ADD_OSDBL 0x6c
#define MAX7456ADD_STAT 0xA0
#define NVM_RAM_SIZE 54
#define WRITE_NVR 0xA0
#define STATUS_REG_NVR_BUSY 0x20
/** Line multiples, for convenience & one less op at runtime **/
#define LINE 30
#define LINE01 0
#define LINE02 30
#define LINE03 60
#define LINE04 90
#define LINE05 120
#define LINE06 150
#define LINE07 180
#define LINE08 210
#define LINE09 240
#define LINE10 270
#define LINE11 300
#define LINE12 330
#define LINE13 360
#define LINE14 390
#define LINE15 420
#define LINE16 450
/** PAL or NTSC, value is number of chars total */
#define VIDEO_BUFFER_CHARS_NTSC 390
#define VIDEO_BUFFER_CHARS_PAL 480
#define VIDEO_LINES_NTSC 13
#define VIDEO_LINES_PAL 16
enum VIDEO_TYPES { AUTO = 0, PAL, NTSC };
extern uint16_t maxScreenSize;
void max7456Init(uint8_t system);
void max7456DrawScreen(void);
void max7456WriteNvm(uint8_t char_address, const uint8_t *font_data);
uint8_t max7456GetRowsCount(void);
void max7456Write(uint8_t x, uint8_t y, const char *buff);
void max7456WriteChar(uint8_t x, uint8_t y, uint8_t c);
void max7456ClearScreen(void);
void max7456RefreshAll(void);
uint8_t* max7456GetScreenBuffer(void);
#ifdef MAX7456_DMA_CHANNEL_TX
bool max7456DmaInProgres(void);
#endif // MAX7456_DMA_CHANNEL_TX

View file

@ -0,0 +1,223 @@
/* @file max7456_symbols.h
* @brief max7456 symbols for the mwosd font set
*
* @author Nathan Tsoi nathan@vertile.com
*
* Copyright (C) 2016 Nathan Tsoi
*
* This program 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.
*
* This program 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 this program. If not, see <http://www.gnu.org/licenses/>
*/
#pragma once
#ifdef USE_MAX7456
// Character Symbols
#define SYM_BLANK 0x20
// Satellite Graphics
#define SYM_SAT_L 0x1E
#define SYM_SAT_R 0x1F
//#define SYM_SAT 0x0F // Not used
// Degrees Icon for HEADING/DIRECTION HOME
#define SYM_DEGREES 0xBD
// Direction arrows
#define SYM_ARROW_SOUTH 0x60
#define SYM_ARROW_2 0x61
#define SYM_ARROW_3 0x62
#define SYM_ARROW_4 0x63
#define SYM_ARROW_EAST 0x64
#define SYM_ARROW_6 0x65
#define SYM_ARROW_7 0x66
#define SYM_ARROW_8 0x67
#define SYM_ARROW_NORTH 0x68
#define SYM_ARROW_10 0x69
#define SYM_ARROW_11 0x6A
#define SYM_ARROW_12 0x6B
#define SYM_ARROW_WEST 0x6C
#define SYM_ARROW_14 0x6D
#define SYM_ARROW_15 0x6E
#define SYM_ARROW_16 0x6F
// Heading Graphics
#define SYM_HEADING_N 0x18
#define SYM_HEADING_S 0x19
#define SYM_HEADING_E 0x1A
#define SYM_HEADING_W 0x1B
#define SYM_HEADING_DIVIDED_LINE 0x1C
#define SYM_HEADING_LINE 0x1D
// FRSKY HUB
#define SYM_CELL0 0xF0
#define SYM_CELL1 0xF1
#define SYM_CELL2 0xF2
#define SYM_CELL3 0xF3
#define SYM_CELL4 0xF4
#define SYM_CELL5 0xF5
#define SYM_CELL6 0xF6
#define SYM_CELL7 0xF7
#define SYM_CELL8 0xF8
#define SYM_CELL9 0xF9
#define SYM_CELLA 0xFA
#define SYM_CELLB 0xFB
#define SYM_CELLC 0xFC
#define SYM_CELLD 0xFD
#define SYM_CELLE 0xFE
#define SYM_CELLF 0xC3
// Map mode
#define SYM_HOME 0x04
#define SYM_AIRCRAFT 0x05
#define SYM_RANGE_100 0x21
#define SYM_RANGE_500 0x22
#define SYM_RANGE_2500 0x23
#define SYM_RANGE_MAX 0x24
#define SYM_DIRECTION 0x72
// GPS Coordinates and Altitude
#define SYM_LAT 0xCA
#define SYM_LON 0xCB
#define SYM_ALT 0xCC
// GPS Mode and Autopilot
#define SYM_3DFIX 0xDF
#define SYM_HOLD 0xEF
#define SYM_G_HOME 0xFF
#define SYM_GHOME 0x9D
#define SYM_GHOME1 0x9E
#define SYM_GHOLD 0xCD
#define SYM_GHOLD1 0xCE
#define SYM_GMISSION 0xB5
#define SYM_GMISSION1 0xB6
#define SYM_GLAND 0xB7
#define SYM_GLAND1 0xB8
// Gimbal active Mode
#define SYM_GIMBAL 0x16
#define SYM_GIMBAL1 0x17
// Sensor´s Presence
#define SYM_ACC 0xA0
#define SYM_MAG 0xA1
#define SYM_BAR 0xA2
#define SYM_GPS 0xA3
#define SYM_MAN 0xC0
#define SYM_MAN1 0xC1
#define SYM_MAN2 0xC2
#define SYM_CHECK 0xBE
#define SYM_BARO10 0xB7
#define SYM_BARO11 0xB8
#define SYM_MAG10 0xB5
#define SYM_MAG11 0xB6
// AH Center screen Graphics
#define SYM_AH_CENTER_LINE 0x26
#define SYM_AH_CENTER_LINE_RIGHT 0x27
#define SYM_AH_CENTER 0x7E
#define SYM_AH_RIGHT 0x02
#define SYM_AH_LEFT 0x03
#define SYM_AH_DECORATION_UP 0xC9
#define SYM_AH_DECORATION_DOWN 0xCF
// AH Bars
#define SYM_AH_BAR9_0 0x80
// Temperature
#define SYM_TEMP_F 0x0D
#define SYM_TEMP_C 0x0E
// Batt evolution
#define SYM_BATT_FULL 0x90
#define SYM_BATT_5 0x91
#define SYM_BATT_4 0x92
#define SYM_BATT_3 0x93
#define SYM_BATT_2 0x94
#define SYM_BATT_1 0x95
#define SYM_BATT_EMPTY 0x96
// Vario
#define SYM_VARIO 0x7F
// Glidescope
#define SYM_GLIDESCOPE 0xE0
// Batt Icon´s
#define SYM_MAIN_BATT 0x97
#define SYM_VID_BAT 0xBF
// Unit Icon´s (Metric)
#define SYM_MS 0x9F
#define SYM_KMH 0xA5
#define SYM_ALTM 0xA7
#define SYM_DISTHOME_M 0xBB
#define SYM_M 0x0C
// Unit Icon´s (Imperial)
#define SYM_FTS 0x99
#define SYM_MPH 0xA6
#define SYM_ALTFT 0xA8
#define SYM_DISTHOME_FT 0xB9
#define SYM_FT 0x0F
// Voltage and amperage
#define SYM_VOLT 0x06
#define SYM_AMP 0x9A
#define SYM_MAH 0x07
#define SYM_WATT 0x57
// Flying Mode
#define SYM_ACRO 0xAE
#define SYM_ACROGY 0x98
#define SYM_ACRO1 0xAF
#define SYM_STABLE 0xAC
#define SYM_STABLE1 0xAD
#define SYM_HORIZON 0xC4
#define SYM_HORIZON1 0xC5
#define SYM_PASS 0xAA
#define SYM_PASS1 0xAB
#define SYM_AIR 0xEA
#define SYM_AIR1 0xEB
#define SYM_PLUS 0x89
// Note, these change with scrolling enabled (scrolling is TODO)
//#define SYM_AH_DECORATION_LEFT 0x13
//#define SYM_AH_DECORATION_RIGHT 0x13
#define SYM_AH_DECORATION 0x13
// Time
#define SYM_ON_M 0x9B
#define SYM_FLY_M 0x9C
#define SYM_ON_H 0x70
#define SYM_FLY_H 0x71
// Throttle Position (%)
#define SYM_THR 0x04
#define SYM_THR1 0x05
// RSSI
#define SYM_RSSI 0x01
// Menu cursor
#define SYM_CURSOR SYM_AH_LEFT
//Misc
#define SYM_COLON 0x2D
//sport
#define SYM_MIN 0xB3
#define SYM_AVG 0xB4
#endif // USE_MAX7456

View file

@ -33,6 +33,8 @@
#include "common/maths.h" #include "common/maths.h"
#include "common/printf.h" #include "common/printf.h"
#include "cms/cms.h"
#include "drivers/logging.h" #include "drivers/logging.h"
#include "drivers/nvic.h" #include "drivers/nvic.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
@ -82,6 +84,8 @@
#include "io/asyncfatfs/asyncfatfs.h" #include "io/asyncfatfs/asyncfatfs.h"
#include "io/pwmdriver_i2c.h" #include "io/pwmdriver_i2c.h"
#include "io/serial_cli.h" #include "io/serial_cli.h"
#include "io/osd.h"
#include "io/displayport_msp.h"
#include "msp/msp_serial.h" #include "msp/msp_serial.h"
@ -444,12 +448,22 @@ void init(void)
initBoardAlignment(&masterConfig.boardAlignment); initBoardAlignment(&masterConfig.boardAlignment);
#ifdef DISPLAY #ifdef CMS
cmsInit();
#endif
#ifdef USE_DISPLAY
if (feature(FEATURE_DISPLAY)) { if (feature(FEATURE_DISPLAY)) {
displayInit(&masterConfig.rxConfig); displayInit(&masterConfig.rxConfig);
} }
#endif #endif
#ifdef OSD
if (feature(FEATURE_OSD)) {
osdInit();
}
#endif
#ifdef GPS #ifdef GPS
if (feature(FEATURE_GPS)) { if (feature(FEATURE_GPS)) {
gpsPreInit(&masterConfig.gpsConfig); gpsPreInit(&masterConfig.gpsConfig);
@ -479,6 +493,10 @@ void init(void)
mspSerialInit(mspFcInit()); mspSerialInit(mspFcInit());
#if defined(USE_MSP_DISPLAYPORT) && defined(CMS)
cmsDisplayPortRegister(displayPortMspInit());
#endif
#ifdef USE_CLI #ifdef USE_CLI
cliInit(&masterConfig.serialConfig); cliInit(&masterConfig.serialConfig);
#endif #endif

View file

@ -21,6 +21,8 @@
#include "platform.h" #include "platform.h"
#include "cms/cms.h"
#include "common/axis.h" #include "common/axis.h"
#include "common/color.h" #include "common/color.h"
#include "common/maths.h" #include "common/maths.h"
@ -43,6 +45,7 @@
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"
#include "io/osd.h"
#include "io/motors.h" #include "io/motors.h"
#include "io/servos.h" #include "io/servos.h"
#include "io/pwmdriver_i2c.h" #include "io/pwmdriver_i2c.h"
@ -233,6 +236,15 @@ void taskAcc(uint32_t currentTime)
} }
#endif #endif
#ifdef OSD
void taskUpdateOsd(uint32_t currentTime)
{
if (feature(FEATURE_OSD)) {
osdUpdate(currentTime);
}
}
#endif
cfTask_t cfTasks[TASK_COUNT] = { cfTask_t cfTasks[TASK_COUNT] = {
[TASK_SYSTEM] = { [TASK_SYSTEM] = {
.taskName = "SYSTEM", .taskName = "SYSTEM",
@ -394,6 +406,24 @@ cfTask_t cfTasks[TASK_COUNT] = {
.staticPriority = TASK_PRIORITY_IDLE, .staticPriority = TASK_PRIORITY_IDLE,
}, },
#endif #endif
#ifdef OSD
[TASK_OSD] = {
.taskName = "OSD",
.taskFunc = taskUpdateOsd,
.desiredPeriod = 1000000 / 60, // 60 Hz
.staticPriority = TASK_PRIORITY_LOW,
},
#endif
#ifdef CMS
[TASK_CMS] = {
.taskName = "CMS",
.taskFunc = cmsHandler,
.desiredPeriod = 1000000 / 60, // 60 Hz
.staticPriority = TASK_PRIORITY_LOW,
},
#endif
}; };
void fcTasksInit(void) void fcTasksInit(void)
@ -460,4 +490,16 @@ void fcTasksInit(void)
#ifdef USE_PMW_SERVO_DRIVER #ifdef USE_PMW_SERVO_DRIVER
setTaskEnabled(TASK_PWMDRIVER, feature(FEATURE_PWM_SERVO_DRIVER)); setTaskEnabled(TASK_PWMDRIVER, feature(FEATURE_PWM_SERVO_DRIVER));
#endif #endif
#ifdef OSD
setTaskEnabled(TASK_OSD, feature(FEATURE_OSD));
#endif
#ifdef CMS
#ifdef USE_MSP_DISPLAYPORT
setTaskEnabled(TASK_CMS, true);
#else
setTaskEnabled(TASK_CMS, feature(FEATURE_OSD) || feature(FEATURE_DISPLAY));
#endif
#endif
} }

752
src/main/io/dashboard.c Normal file
View file

@ -0,0 +1,752 @@
/*
* 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 "platform.h"
#ifdef USE_DASHBOARD
#include "common/utils.h"
#include "build/version.h"
#include "build/debug.h"
#include "build/build_config.h"
#include "drivers/system.h"
#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"
#include "common/typeconversion.h"
#include "sensors/battery.h"
#include "sensors/sensors.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/gyro.h"
#include "config/config.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "io/displayport_oled.h"
#ifdef GPS_NOT_YET
#include "io/gps.h"
//#include "flight/navigation.h"
#endif
#include "config/feature.h"
#include "config/config_profile.h"
#include "io/dashboard.h"
#include "rx/rx.h"
#include "scheduler/scheduler.h"
extern profile_t *currentProfile;
controlRateConfig_t *getControlRateConfig(uint8_t profileIndex);
#define MICROSECONDS_IN_A_SECOND (1000 * 1000)
#define DISPLAY_UPDATE_FREQUENCY (MICROSECONDS_IN_A_SECOND / 5)
#define PAGE_CYCLE_FREQUENCY (MICROSECONDS_IN_A_SECOND * 5)
static uint32_t nextDisplayUpdateAt = 0;
static bool dashboardPresent = false;
static rxConfig_t *rxConfig;
static displayPort_t *displayPort;
#define PAGE_TITLE_LINE_COUNT 1
static char lineBuffer[SCREEN_CHARACTER_COLUMN_COUNT + 1];
#define HALF_SCREEN_CHARACTER_COLUMN_COUNT (SCREEN_CHARACTER_COLUMN_COUNT / 2)
#define IS_SCREEN_CHARACTER_COLUMN_COUNT_ODD (SCREEN_CHARACTER_COLUMN_COUNT & 1)
static const char* const pageTitles[] = {
"CLEANFLIGHT",
"ARMED",
"BATTERY",
"SENSORS",
"RX",
"PROFILE"
#ifndef SKIP_TASK_STATISTICS
,"TASKS"
#endif
#ifdef GPS_NOT_YET
,"GPS"
#endif
#ifdef ENABLE_DEBUG_DASHBOARD_PAGE
,"DEBUG"
#endif
};
#define PAGE_COUNT (PAGE_RX + 1)
const pageId_e cyclePageIds[] = {
PAGE_PROFILE,
#ifdef GPS_NOT_YET
PAGE_GPS,
#endif
PAGE_RX,
PAGE_BATTERY,
PAGE_SENSORS
#ifndef SKIP_TASK_STATISTICS
,PAGE_TASKS
#endif
#ifdef ENABLE_DEBUG_DASHBOARD_PAGE
,PAGE_DEBUG,
#endif
};
#define CYCLE_PAGE_ID_COUNT (sizeof(cyclePageIds) / sizeof(cyclePageIds[0]))
static const char* tickerCharacters = "|/-\\"; // use 2/4/8 characters so that the divide is optimal.
#define TICKER_CHARACTER_COUNT (sizeof(tickerCharacters) / sizeof(char))
typedef enum {
PAGE_STATE_FLAG_NONE = 0,
PAGE_STATE_FLAG_CYCLE_ENABLED = (1 << 0),
PAGE_STATE_FLAG_FORCE_PAGE_CHANGE = (1 << 1)
} pageFlags_e;
typedef struct pageState_s {
bool pageChanging;
pageId_e pageId;
pageId_e pageIdBeforeArming;
uint8_t pageFlags;
uint8_t cycleIndex;
uint32_t nextPageAt;
} pageState_t;
static pageState_t pageState;
void resetDisplay(void) {
dashboardPresent = ug2864hsweg01InitI2C();
}
void LCDprint(uint8_t i) {
i2c_OLED_send_char(i);
}
void padLineBuffer(void)
{
uint8_t length = strlen(lineBuffer);
while (length < sizeof(lineBuffer) - 1) {
lineBuffer[length++] = ' ';
}
lineBuffer[length] = 0;
}
void padHalfLineBuffer(void)
{
uint8_t halfLineIndex = sizeof(lineBuffer) / 2;
uint8_t length = strlen(lineBuffer);
while (length < halfLineIndex - 1) {
lineBuffer[length++] = ' ';
}
lineBuffer[length] = 0;
}
// LCDbar(n,v) : draw a bar graph - n number of chars for width, v value in % to display
void drawHorizonalPercentageBar(uint8_t width,uint8_t percent) {
uint8_t i, j;
if (percent > 100)
percent = 100;
j = (width * percent) / 100;
for (i = 0; i < j; i++)
LCDprint(159); // full
if (j < width)
LCDprint(154 + (percent * width * 5 / 100 - 5 * j)); // partial fill
for (i = j + 1; i < width; i++)
LCDprint(154); // empty
}
#if 0
void fillScreenWithCharacters()
{
for (uint8_t row = 0; row < SCREEN_CHARACTER_ROW_COUNT; row++) {
for (uint8_t column = 0; column < SCREEN_CHARACTER_COLUMN_COUNT; column++) {
i2c_OLED_set_xy(column, row);
i2c_OLED_send_char('A' + column);
}
}
}
#endif
void updateTicker(void)
{
static uint8_t tickerIndex = 0;
i2c_OLED_set_xy(SCREEN_CHARACTER_COLUMN_COUNT - 1, 0);
i2c_OLED_send_char(tickerCharacters[tickerIndex]);
tickerIndex++;
tickerIndex = tickerIndex % TICKER_CHARACTER_COUNT;
}
void updateRxStatus(void)
{
i2c_OLED_set_xy(SCREEN_CHARACTER_COLUMN_COUNT - 2, 0);
char rxStatus = '!';
if (rxIsReceivingSignal()) {
rxStatus = 'r';
} if (rxAreFlightChannelsValid()) {
rxStatus = 'R';
}
i2c_OLED_send_char(rxStatus);
}
void updateFailsafeStatus(void)
{
char failsafeIndicator = '?';
switch (failsafePhase()) {
case FAILSAFE_IDLE:
failsafeIndicator = '-';
break;
case FAILSAFE_RX_LOSS_DETECTED:
failsafeIndicator = 'R';
break;
case FAILSAFE_LANDING:
failsafeIndicator = 'l';
break;
case FAILSAFE_LANDED:
failsafeIndicator = 'L';
break;
case FAILSAFE_RX_LOSS_MONITORING:
failsafeIndicator = 'M';
break;
case FAILSAFE_RX_LOSS_RECOVERED:
failsafeIndicator = 'r';
break;
}
i2c_OLED_set_xy(SCREEN_CHARACTER_COLUMN_COUNT - 3, 0);
i2c_OLED_send_char(failsafeIndicator);
}
void showTitle()
{
i2c_OLED_set_line(0);
i2c_OLED_send_string(pageTitles[pageState.pageId]);
}
void handlePageChange(void)
{
i2c_OLED_clear_display_quick();
showTitle();
}
void drawRxChannel(uint8_t channelIndex, uint8_t width)
{
uint32_t percentage;
LCDprint(rcChannelLetters[channelIndex]);
percentage = (constrain(rcData[channelIndex], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN);
drawHorizonalPercentageBar(width - 1, percentage);
}
#define RX_CHANNELS_PER_PAGE_COUNT 14
void showRxPage(void)
{
for (uint8_t channelIndex = 0; channelIndex < rxRuntimeConfig.channelCount && channelIndex < RX_CHANNELS_PER_PAGE_COUNT; channelIndex += 2) {
i2c_OLED_set_line((channelIndex / 2) + PAGE_TITLE_LINE_COUNT);
drawRxChannel(channelIndex, HALF_SCREEN_CHARACTER_COLUMN_COUNT);
if (channelIndex >= rxRuntimeConfig.channelCount) {
continue;
}
if (IS_SCREEN_CHARACTER_COLUMN_COUNT_ODD) {
LCDprint(' ');
}
drawRxChannel(channelIndex + PAGE_TITLE_LINE_COUNT, HALF_SCREEN_CHARACTER_COLUMN_COUNT);
}
}
void showWelcomePage(void)
{
uint8_t rowIndex = PAGE_TITLE_LINE_COUNT;
tfp_sprintf(lineBuffer, "v%s (%s)", FC_VERSION_STRING, shortGitRevision);
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(targetName);
}
void showArmedPage(void)
{
}
void showProfilePage(void)
{
uint8_t rowIndex = PAGE_TITLE_LINE_COUNT;
tfp_sprintf(lineBuffer, "Profile: %d", getCurrentProfile());
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
static const char* const axisTitles[3] = {"ROL", "PIT", "YAW"};
const pidProfile_t *pidProfile = &currentProfile->pidProfile;
for (int axis = 0; axis < 3; ++axis) {
tfp_sprintf(lineBuffer, "%s P:%3d I:%3d D:%3d",
axisTitles[axis],
pidProfile->P8[axis],
pidProfile->I8[axis],
pidProfile->D8[axis]
);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
}
const uint8_t currentRateProfileIndex = getCurrentControlRateProfile();
tfp_sprintf(lineBuffer, "Rate profile: %d", currentRateProfileIndex);
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
const controlRateConfig_t *controlRateConfig = getControlRateConfig(currentRateProfileIndex);
tfp_sprintf(lineBuffer, "RCE: %d, RCR: %d",
controlRateConfig->rcExpo8,
controlRateConfig->rcRate8
);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
tfp_sprintf(lineBuffer, "RR:%d PR:%d YR:%d",
controlRateConfig->rates[FD_ROLL],
controlRateConfig->rates[FD_PITCH],
controlRateConfig->rates[FD_YAW]
);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
}
#ifdef GPS_NOTYET
#define SATELLITE_COUNT (sizeof(GPS_svinfo_cno) / sizeof(GPS_svinfo_cno[0]))
#define SATELLITE_GRAPH_LEFT_OFFSET ((SCREEN_CHARACTER_COLUMN_COUNT - SATELLITE_COUNT) / 2)
#endif
#ifdef GPS_NOTYET
void showGpsPage() {
uint8_t rowIndex = PAGE_TITLE_LINE_COUNT;
static uint8_t gpsTicker = 0;
static uint32_t lastGPSSvInfoReceivedCount = 0;
if (GPS_svInfoReceivedCount != lastGPSSvInfoReceivedCount) {
lastGPSSvInfoReceivedCount = GPS_svInfoReceivedCount;
gpsTicker++;
gpsTicker = gpsTicker % TICKER_CHARACTER_COUNT;
}
i2c_OLED_set_xy(0, rowIndex);
i2c_OLED_send_char(tickerCharacters[gpsTicker]);
i2c_OLED_set_xy(MAX(0, SATELLITE_GRAPH_LEFT_OFFSET), rowIndex++);
uint32_t index;
for (index = 0; index < SATELLITE_COUNT && index < SCREEN_CHARACTER_COLUMN_COUNT; index++) {
uint8_t bargraphOffset = ((uint16_t) GPS_svinfo_cno[index] * VERTICAL_BARGRAPH_CHARACTER_COUNT) / (GPS_DBHZ_MAX - 1);
bargraphOffset = MIN(bargraphOffset, VERTICAL_BARGRAPH_CHARACTER_COUNT - 1);
i2c_OLED_send_char(VERTICAL_BARGRAPH_ZERO_CHARACTER + bargraphOffset);
}
char fixChar = STATE(GPS_FIX) ? 'Y' : 'N';
tfp_sprintf(lineBuffer, "Sats: %d Fix: %c", GPS_numSat, fixChar);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
tfp_sprintf(lineBuffer, "La/Lo: %d/%d", GPS_coord[LAT] / GPS_DEGREES_DIVIDER, GPS_coord[LON] / GPS_DEGREES_DIVIDER);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
tfp_sprintf(lineBuffer, "Spd: %d", GPS_speed);
padHalfLineBuffer();
i2c_OLED_set_line(rowIndex);
i2c_OLED_send_string(lineBuffer);
tfp_sprintf(lineBuffer, "GC: %d", GPS_ground_course);
padHalfLineBuffer();
i2c_OLED_set_xy(HALF_SCREEN_CHARACTER_COLUMN_COUNT, rowIndex++);
i2c_OLED_send_string(lineBuffer);
tfp_sprintf(lineBuffer, "RX: %d", GPS_packetCount);
padHalfLineBuffer();
i2c_OLED_set_line(rowIndex);
i2c_OLED_send_string(lineBuffer);
tfp_sprintf(lineBuffer, "ERRs: %d", gpsData.errors, gpsData.timeouts);
padHalfLineBuffer();
i2c_OLED_set_xy(HALF_SCREEN_CHARACTER_COLUMN_COUNT, rowIndex++);
i2c_OLED_send_string(lineBuffer);
tfp_sprintf(lineBuffer, "Dt: %d", gpsData.lastMessage - gpsData.lastLastMessage);
padHalfLineBuffer();
i2c_OLED_set_line(rowIndex);
i2c_OLED_send_string(lineBuffer);
tfp_sprintf(lineBuffer, "TOs: %d", gpsData.timeouts);
padHalfLineBuffer();
i2c_OLED_set_xy(HALF_SCREEN_CHARACTER_COLUMN_COUNT, rowIndex++);
i2c_OLED_send_string(lineBuffer);
strncpy(lineBuffer, gpsPacketLog, GPS_PACKET_LOG_ENTRY_COUNT);
padHalfLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
#ifdef GPS_PH_DEBUG
tfp_sprintf(lineBuffer, "Angles: P:%d R:%d", GPS_angle[PITCH], GPS_angle[ROLL]);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
#endif
#if 0
tfp_sprintf(lineBuffer, "%d %d %d %d", debug[0], debug[1], debug[2], debug[3]);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
#endif
}
#endif
void showBatteryPage(void)
{
uint8_t rowIndex = PAGE_TITLE_LINE_COUNT;
if (feature(FEATURE_VBAT)) {
tfp_sprintf(lineBuffer, "Volts: %d.%1d Cells: %d", vbat / 10, vbat % 10, batteryCellCount);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
uint8_t batteryPercentage = calculateBatteryPercentage();
i2c_OLED_set_line(rowIndex++);
drawHorizonalPercentageBar(SCREEN_CHARACTER_COLUMN_COUNT, batteryPercentage);
}
if (feature(FEATURE_CURRENT_METER)) {
tfp_sprintf(lineBuffer, "Amps: %d.%2d mAh: %d", amperage / 100, amperage % 100, mAhDrawn);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
uint8_t capacityPercentage = calculateBatteryCapacityRemainingPercentage();
i2c_OLED_set_line(rowIndex++);
drawHorizonalPercentageBar(SCREEN_CHARACTER_COLUMN_COUNT, capacityPercentage);
}
}
void showSensorsPage(void)
{
uint8_t rowIndex = PAGE_TITLE_LINE_COUNT;
static const char *format = "%s %5d %5d %5d";
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(" X Y Z");
if (sensors(SENSOR_ACC)) {
tfp_sprintf(lineBuffer, format, "ACC", accSmooth[X], accSmooth[Y], accSmooth[Z]);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
}
if (sensors(SENSOR_GYRO)) {
tfp_sprintf(lineBuffer, format, "GYR", gyroADC[X], gyroADC[Y], gyroADC[Z]);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
}
#ifdef MAG
if (sensors(SENSOR_MAG)) {
tfp_sprintf(lineBuffer, format, "MAG", magADC[X], magADC[Y], magADC[Z]);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
}
#endif
tfp_sprintf(lineBuffer, format, "I&H", attitude.values.roll, attitude.values.pitch, DECIDEGREES_TO_DEGREES(attitude.values.yaw));
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
/*
uint8_t length;
ftoa(EstG.A[X], lineBuffer);
length = strlen(lineBuffer);
while (length < HALF_SCREEN_CHARACTER_COLUMN_COUNT) {
lineBuffer[length++] = ' ';
lineBuffer[length+1] = 0;
}
ftoa(EstG.A[Y], lineBuffer + length);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
ftoa(EstG.A[Z], lineBuffer);
length = strlen(lineBuffer);
while (length < HALF_SCREEN_CHARACTER_COLUMN_COUNT) {
lineBuffer[length++] = ' ';
lineBuffer[length+1] = 0;
}
ftoa(smallAngle, lineBuffer + length);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
*/
}
#ifndef SKIP_TASK_STATISTICS
void showTasksPage(void)
{
uint8_t rowIndex = PAGE_TITLE_LINE_COUNT;
static const char *format = "%2d%6d%5d%4d%4d";
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string("Task max avg mx% av%");
cfTaskInfo_t taskInfo;
for (cfTaskId_e taskId = 0; taskId < TASK_COUNT; ++taskId) {
getTaskInfo(taskId, &taskInfo);
if (taskInfo.isEnabled && taskId != TASK_SERIAL) {// don't waste a line of the display showing serial taskInfo
const int taskFrequency = (int)(1000000.0f / ((float)taskInfo.latestDeltaTime));
const int maxLoad = (taskInfo.maxExecutionTime * taskFrequency + 5000) / 10000;
const int averageLoad = (taskInfo.averageExecutionTime * taskFrequency + 5000) / 10000;
tfp_sprintf(lineBuffer, format, taskId, taskInfo.maxExecutionTime, taskInfo.averageExecutionTime, maxLoad, averageLoad);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
if (rowIndex > SCREEN_CHARACTER_ROW_COUNT) {
break;
}
}
}
}
#endif
#ifdef ENABLE_DEBUG_DASHBOARD_PAGE
void showDebugPage(void)
{
uint8_t rowIndex;
for (rowIndex = 0; rowIndex < 4; rowIndex++) {
tfp_sprintf(lineBuffer, "%d = %5d", rowIndex, debug[rowIndex]);
padLineBuffer();
i2c_OLED_set_line(rowIndex + PAGE_TITLE_LINE_COUNT);
i2c_OLED_send_string(lineBuffer);
}
}
#endif
void dashboardUpdate(uint32_t currentTime)
{
static uint8_t previousArmedState = 0;
#ifdef CMS
if (displayIsGrabbed(displayPort)) {
return;
}
#endif
const bool updateNow = (int32_t)(currentTime - nextDisplayUpdateAt) >= 0L;
if (!updateNow) {
return;
}
nextDisplayUpdateAt = currentTime + DISPLAY_UPDATE_FREQUENCY;
bool armedState = ARMING_FLAG(ARMED) ? true : false;
bool armedStateChanged = armedState != previousArmedState;
previousArmedState = armedState;
if (armedState) {
if (!armedStateChanged) {
return;
}
pageState.pageIdBeforeArming = pageState.pageId;
pageState.pageId = PAGE_ARMED;
pageState.pageChanging = true;
} else {
if (armedStateChanged) {
pageState.pageFlags |= PAGE_STATE_FLAG_FORCE_PAGE_CHANGE;
pageState.pageId = pageState.pageIdBeforeArming;
}
pageState.pageChanging = (pageState.pageFlags & PAGE_STATE_FLAG_FORCE_PAGE_CHANGE) ||
(((int32_t)(currentTime - pageState.nextPageAt) >= 0L && (pageState.pageFlags & PAGE_STATE_FLAG_CYCLE_ENABLED)));
if (pageState.pageChanging && (pageState.pageFlags & PAGE_STATE_FLAG_CYCLE_ENABLED)) {
pageState.cycleIndex++;
pageState.cycleIndex = pageState.cycleIndex % CYCLE_PAGE_ID_COUNT;
pageState.pageId = cyclePageIds[pageState.cycleIndex];
}
}
if (pageState.pageChanging) {
pageState.pageFlags &= ~PAGE_STATE_FLAG_FORCE_PAGE_CHANGE;
pageState.nextPageAt = currentTime + PAGE_CYCLE_FREQUENCY;
// Some OLED displays do not respond on the first initialisation so refresh the display
// when the page changes in the hopes the hardware responds. This also allows the
// user to power off/on the display or connect it while powered.
resetDisplay();
if (!dashboardPresent) {
return;
}
handlePageChange();
}
if (!dashboardPresent) {
return;
}
switch(pageState.pageId) {
case PAGE_WELCOME:
showWelcomePage();
break;
case PAGE_ARMED:
showArmedPage();
break;
case PAGE_BATTERY:
showBatteryPage();
break;
case PAGE_SENSORS:
showSensorsPage();
break;
case PAGE_RX:
showRxPage();
break;
case PAGE_PROFILE:
showProfilePage();
break;
#ifndef SKIP_TASK_STATISTICS
case PAGE_TASKS:
showTasksPage();
break;
#endif
#ifdef GPS_NOTYET
case PAGE_GPS:
if (feature(FEATURE_GPS)) {
showGpsPage();
} else {
pageState.pageFlags |= PAGE_STATE_FLAG_FORCE_PAGE_CHANGE;
}
break;
#endif
#ifdef ENABLE_DEBUG_DASHBOARD_PAGE
case PAGE_DEBUG:
showDebugPage();
break;
#endif
}
if (!armedState) {
updateFailsafeStatus();
updateRxStatus();
updateTicker();
}
}
void dashboardSetPage(pageId_e pageId)
{
pageState.pageId = pageId;
pageState.pageFlags |= PAGE_STATE_FLAG_FORCE_PAGE_CHANGE;
}
void dashboardInit(rxConfig_t *rxConfigToUse)
{
delay(200);
resetDisplay();
delay(200);
displayPort = displayPortOledInit();
#if defined(CMS)
cmsDisplayPortRegister(displayPort);
#endif
rxConfig = rxConfigToUse;
memset(&pageState, 0, sizeof(pageState));
dashboardSetPage(PAGE_WELCOME);
dashboardUpdate(micros());
dashboardSetNextPageChangeAt(micros() + (1000 * 1000 * 5));
}
void dashboardShowFixedPage(pageId_e pageId)
{
dashboardSetPage(pageId);
dashboardDisablePageCycling();
}
void dashboardSetNextPageChangeAt(uint32_t futureMicros)
{
pageState.nextPageAt = futureMicros;
}
void dashboardEnablePageCycling(void)
{
pageState.pageFlags |= PAGE_STATE_FLAG_CYCLE_ENABLED;
}
void dashboardResetPageCycling(void)
{
pageState.cycleIndex = CYCLE_PAGE_ID_COUNT - 1; // start at first page
}
void dashboardDisablePageCycling(void)
{
pageState.pageFlags &= ~PAGE_STATE_FLAG_CYCLE_ENABLED;
}
#endif // USE_DASHBOARD

47
src/main/io/dashboard.h Normal file
View file

@ -0,0 +1,47 @@
/*
* 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/>.
*/
#define ENABLE_DEBUG_DASHBOARD_PAGE
typedef enum {
PAGE_WELCOME,
PAGE_ARMED,
PAGE_BATTERY,
PAGE_SENSORS,
PAGE_RX,
PAGE_PROFILE,
#ifndef SKIP_TASK_STATISTICS
PAGE_TASKS,
#endif
#ifdef GPS
PAGE_GPS,
#endif
#ifdef ENABLE_DEBUG_DASHBOARD_PAGE
PAGE_DEBUG,
#endif
} pageId_e;
struct rxConfig_s;
void dashboardInit(struct rxConfig_s *intialRxConfig);
void dashboardUpdate(uint32_t currentTime);
void dashboardShowFixedPage(pageId_e pageId);
void dashboardEnablePageCycling(void);
void dashboardDisablePageCycling(void);
void dashboardResetPageCycling(void);
void dashboardSetNextPageChangeAt(uint32_t futureMicros);

View file

@ -0,0 +1,107 @@
/*
* 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 "platform.h"
#ifdef OSD
#include "common/utils.h"
#include "config/config_master.h"
#include "drivers/display.h"
#include "drivers/max7456.h"
displayPort_t max7456DisplayPort; // Referenced from osd.c
extern uint16_t refreshTimeout;
static int grab(displayPort_t *displayPort)
{
UNUSED(displayPort);
osdResetAlarms();
displayPort->isGrabbed = true;
refreshTimeout = 0;
return 0;
}
static int release(displayPort_t *displayPort)
{
UNUSED(displayPort);
displayPort->isGrabbed = false;
return 0;
}
static int clearScreen(displayPort_t *displayPort)
{
UNUSED(displayPort);
max7456ClearScreen();
return 0;
}
static int write(displayPort_t *displayPort, uint8_t x, uint8_t y, const char *s)
{
UNUSED(displayPort);
max7456Write(x, y, s);
return 0;
}
static void resync(displayPort_t *displayPort)
{
UNUSED(displayPort);
max7456RefreshAll();
displayPort->rows = max7456GetRowsCount();
displayPort->cols = 30;
}
static int heartbeat(displayPort_t *displayPort)
{
UNUSED(displayPort);
return 0;
}
static uint32_t txBytesFree(const displayPort_t *displayPort)
{
UNUSED(displayPort);
return UINT32_MAX;
}
static displayPortVTable_t max7456VTable = {
.grab = grab,
.release = release,
.clear = clearScreen,
.write = write,
.heartbeat = heartbeat,
.resync = resync,
.txBytesFree = txBytesFree,
};
displayPort_t *max7456DisplayPortInit(void)
{
max7456DisplayPort.vTable = &max7456VTable;
max7456DisplayPort.isGrabbed = false;
resync(&max7456DisplayPort);
return &max7456DisplayPort;
}
#endif // OSD

View file

@ -0,0 +1,20 @@
/*
* 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/>.
*/
#pragma once
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

@ -0,0 +1,21 @@
/*
* 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/>.
*/
#pragma once
struct displayPort_s;
struct displayPort_s *displayPortMspInit(void);

View file

@ -0,0 +1,91 @@
/*
* 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 "platform.h"
#include "common/utils.h"
#include "drivers/display.h"
#include "drivers/display_ug2864hsweg01.h"
static displayPort_t oledDisplayPort;
static int oledGrab(displayPort_t *displayPort)
{
UNUSED(displayPort);
return 0;
}
static int oledRelease(displayPort_t *displayPort)
{
UNUSED(displayPort);
return 0;
}
static int oledClear(displayPort_t *displayPort)
{
UNUSED(displayPort);
i2c_OLED_clear_display_quick();
return 0;
}
static int oledWrite(displayPort_t *displayPort, uint8_t x, uint8_t y, const char *s)
{
UNUSED(displayPort);
i2c_OLED_set_xy(x, y);
i2c_OLED_send_string(s);
return 0;
}
static int oledHeartbeat(displayPort_t *displayPort)
{
UNUSED(displayPort);
return 0;
}
static void oledResync(displayPort_t *displayPort)
{
UNUSED(displayPort);
}
static uint32_t oledTxBytesFree(const displayPort_t *displayPort)
{
UNUSED(displayPort);
return UINT32_MAX;
}
static const displayPortVTable_t oledVTable = {
.grab = oledGrab,
.release = oledRelease,
.clear = oledClear,
.write = oledWrite,
.heartbeat = oledHeartbeat,
.resync = oledResync,
.txBytesFree = oledTxBytesFree
};
displayPort_t *displayPortOledInit(void)
{
oledDisplayPort.vTable = &oledVTable;
oledDisplayPort.rows = SCREEN_CHARACTER_ROW_COUNT;
oledDisplayPort.cols = SCREEN_CHARACTER_COLUMN_COUNT;
oledDisplayPort.isGrabbed = false;
return &oledDisplayPort;
}

View file

@ -0,0 +1,20 @@
/*
* 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/>.
*/
#pragma once
displayPort_t *displayPortOledInit(void);

675
src/main/io/osd.c Normal file
View file

@ -0,0 +1,675 @@
/*
* 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/>.
*/
/*
Created by Marcin Baliniak
some functions based on MinimOSD
OSD-CMS separation by jflyper
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <ctype.h>
#include "platform.h"
#ifdef OSD
// XXX Must review what's included
#include "build/version.h"
#include "common/utils.h"
#include "drivers/system.h"
#include "common/axis.h"
#include "io/gimbal.h"
#include "flight/pid.h"
#include "flight/mixer.h"
#include "flight/servos.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
#include "config/feature.h"
#include "drivers/display.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"
#ifdef USE_HARDWARE_REVISION_DETECTION
#include "hardware_revision.h"
#endif
#include "drivers/max7456.h"
#include "drivers/max7456_symbols.h"
#include "common/printf.h"
#include "build/debug.h"
// Character coordinate and attributes
#define OSD_POS(x,y) (x | (y << 5))
#define OSD_X(x) (x & 0x001F)
#define OSD_Y(x) ((x >> 5) & 0x001F)
// Things in both OSD and CMS
#define IS_HI(X) (rcData[X] > 1750)
#define IS_LO(X) (rcData[X] < 1250)
#define IS_MID(X) (rcData[X] > 1250 && rcData[X] < 1750)
bool blinkState = true;
//extern uint8_t RSSI; // TODO: not used?
static uint16_t flyTime = 0;
static uint8_t statRssi;
typedef struct statistic_s {
int16_t max_speed;
int16_t min_voltage; // /10
int16_t max_current; // /10
int16_t min_rssi;
int16_t max_altitude;
} statistic_t;
static statistic_t stats;
uint16_t refreshTimeout = 0;
#define REFRESH_1S 12
static uint8_t armState;
static displayPort_t *osd7456DisplayPort;
#define AH_MAX_PITCH 200 // Specify maximum AHI pitch value displayed. Default 200 = 20.0 degrees
#define AH_MAX_ROLL 400 // Specify maximum AHI roll value displayed. Default 400 = 40.0 degrees
#define AH_SIDEBAR_WIDTH_POS 7
#define AH_SIDEBAR_HEIGHT_POS 3
/**
* Gets the correct altitude symbol for the current unit system
*/
static char osdGetAltitudeSymbol()
{
switch (masterConfig.osdProfile.units) {
case OSD_UNIT_IMPERIAL:
return 0xF;
default:
return 0xC;
}
}
/**
* Converts altitude based on the current unit system.
* @param alt Raw altitude (i.e. as taken from BaroAlt)
*/
static int32_t osdGetAltitude(int32_t alt)
{
switch (masterConfig.osdProfile.units) {
case OSD_UNIT_IMPERIAL:
return (alt * 328) / 100; // Convert to feet / 100
default:
return alt; // Already in metre / 100
}
}
static void osdDrawSingleElement(uint8_t item)
{
if (!VISIBLE(masterConfig.osdProfile.item_pos[item]) || BLINK(masterConfig.osdProfile.item_pos[item]))
return;
uint8_t elemPosX = OSD_X(masterConfig.osdProfile.item_pos[item]);
uint8_t elemPosY = OSD_Y(masterConfig.osdProfile.item_pos[item]);
char buff[32];
switch(item) {
case OSD_RSSI_VALUE:
{
uint16_t osdRssi = rssi * 100 / 1024; // change range
if (osdRssi >= 100)
osdRssi = 99;
buff[0] = SYM_RSSI;
sprintf(buff + 1, "%d", osdRssi);
break;
}
case OSD_MAIN_BATT_VOLTAGE:
{
buff[0] = SYM_BATT_5;
sprintf(buff + 1, "%d.%1dV", vbat / 10, vbat % 10);
break;
}
case OSD_CURRENT_DRAW:
{
buff[0] = SYM_AMP;
sprintf(buff + 1, "%d.%02d", abs(amperage) / 100, abs(amperage) % 100);
break;
}
case OSD_MAH_DRAWN:
{
buff[0] = SYM_MAH;
sprintf(buff + 1, "%d", mAhDrawn);
break;
}
#ifdef GPS_notyet
case OSD_GPS_SATS:
{
buff[0] = 0x1f;
sprintf(buff + 1, "%d", GPS_numSat);
break;
}
case OSD_GPS_SPEED:
{
sprintf(buff, "%d", GPS_speed * 36 / 1000);
break;
}
#endif // GPS
case OSD_ALTITUDE:
{
int32_t alt = osdGetAltitude(BaroAlt);
sprintf(buff, "%c%d.%01d%c", alt < 0 ? '-' : ' ', abs(alt / 100), abs((alt % 100) / 10), osdGetAltitudeSymbol());
break;
}
case OSD_ONTIME:
{
uint32_t seconds = micros() / 1000000;
buff[0] = SYM_ON_M;
sprintf(buff + 1, "%02d:%02d", seconds / 60, seconds % 60);
break;
}
case OSD_FLYTIME:
{
buff[0] = SYM_FLY_M;
sprintf(buff + 1, "%02d:%02d", flyTime / 60, flyTime % 60);
break;
}
case OSD_FLYMODE:
{
char *p = "ACRO";
#if 0
if (isAirmodeActive())
p = "AIR";
#endif
if (FLIGHT_MODE(FAILSAFE_MODE))
p = "!FS";
else if (FLIGHT_MODE(ANGLE_MODE))
p = "STAB";
else if (FLIGHT_MODE(HORIZON_MODE))
p = "HOR";
max7456Write(elemPosX, elemPosY, p);
return;
}
case OSD_CRAFT_NAME:
{
if (strlen(masterConfig.name) == 0)
strcpy(buff, "CRAFT_NAME");
else {
for (uint8_t i = 0; i < MAX_NAME_LENGTH; i++) {
buff[i] = toupper((unsigned char)masterConfig.name[i]);
if (masterConfig.name[i] == 0)
break;
}
}
break;
}
case OSD_THROTTLE_POS:
{
buff[0] = SYM_THR;
buff[1] = SYM_THR1;
sprintf(buff + 2, "%d", (constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN));
break;
}
#ifdef VTX
case OSD_VTX_CHANNEL:
{
sprintf(buff, "CH:%d", current_vtx_channel % CHANNELS_PER_BAND + 1);
break;
}
#endif // VTX
case OSD_CROSSHAIRS:
elemPosX = 14 - 1; // Offset for 1 char to the left
elemPosY = 6;
if (maxScreenSize == VIDEO_BUFFER_CHARS_PAL)
++elemPosY;
buff[0] = SYM_AH_CENTER_LINE;
buff[1] = SYM_AH_CENTER;
buff[2] = SYM_AH_CENTER_LINE_RIGHT;
buff[3] = 0;
break;
case OSD_ARTIFICIAL_HORIZON:
{
elemPosX = 14;
elemPosY = 6 - 4; // Top center of the AH area
int rollAngle = attitude.values.roll;
int pitchAngle = attitude.values.pitch;
if (maxScreenSize == VIDEO_BUFFER_CHARS_PAL)
++elemPosY;
if (pitchAngle > AH_MAX_PITCH)
pitchAngle = AH_MAX_PITCH;
if (pitchAngle < -AH_MAX_PITCH)
pitchAngle = -AH_MAX_PITCH;
if (rollAngle > AH_MAX_ROLL)
rollAngle = AH_MAX_ROLL;
if (rollAngle < -AH_MAX_ROLL)
rollAngle = -AH_MAX_ROLL;
// Convert pitchAngle to y compensation value
pitchAngle = (pitchAngle / 8) - 41; // 41 = 4 * 9 + 5
for (int8_t x = -4; x <= 4; x++) {
int y = (rollAngle * x) / 64;
y -= pitchAngle;
// y += 41; // == 4 * 9 + 5
if (y >= 0 && y <= 81) {
max7456WriteChar(elemPosX + x, elemPosY + (y / 9), (SYM_AH_BAR9_0 + (y % 9)));
}
}
osdDrawSingleElement(OSD_HORIZON_SIDEBARS);
return;
}
case OSD_HORIZON_SIDEBARS:
{
elemPosX = 14;
elemPosY = 6;
if (maxScreenSize == VIDEO_BUFFER_CHARS_PAL)
++elemPosY;
// Draw AH sides
int8_t hudwidth = AH_SIDEBAR_WIDTH_POS;
int8_t hudheight = AH_SIDEBAR_HEIGHT_POS;
for (int8_t y = -hudheight; y <= hudheight; y++) {
max7456WriteChar(elemPosX - hudwidth, elemPosY + y, SYM_AH_DECORATION);
max7456WriteChar(elemPosX + hudwidth, elemPosY + y, SYM_AH_DECORATION);
}
// AH level indicators
max7456WriteChar(elemPosX - hudwidth + 1, elemPosY, SYM_AH_LEFT);
max7456WriteChar(elemPosX + hudwidth - 1, elemPosY, SYM_AH_RIGHT);
return;
}
default:
return;
}
max7456Write(elemPosX, elemPosY, buff);
}
void osdDrawElements(void)
{
max7456ClearScreen();
#if 0
if (currentElement)
osdDrawElementPositioningHelp();
#else
if (false)
;
#endif
#ifdef CMS
else if (sensors(SENSOR_ACC) || displayIsGrabbed(osd7456DisplayPort))
#else
else if (sensors(SENSOR_ACC))
#endif
{
osdDrawSingleElement(OSD_ARTIFICIAL_HORIZON);
osdDrawSingleElement(OSD_CROSSHAIRS);
}
osdDrawSingleElement(OSD_MAIN_BATT_VOLTAGE);
osdDrawSingleElement(OSD_RSSI_VALUE);
osdDrawSingleElement(OSD_FLYTIME);
osdDrawSingleElement(OSD_ONTIME);
osdDrawSingleElement(OSD_FLYMODE);
osdDrawSingleElement(OSD_THROTTLE_POS);
osdDrawSingleElement(OSD_VTX_CHANNEL);
osdDrawSingleElement(OSD_CURRENT_DRAW);
osdDrawSingleElement(OSD_MAH_DRAWN);
osdDrawSingleElement(OSD_CRAFT_NAME);
osdDrawSingleElement(OSD_ALTITUDE);
#ifdef GPS
#ifdef CMS
if (sensors(SENSOR_GPS) || displayIsGrabbed(osd7456DisplayPort))
#else
if (sensors(SENSOR_GPS))
#endif
{
osdDrawSingleElement(OSD_GPS_SATS);
osdDrawSingleElement(OSD_GPS_SPEED);
}
#endif // GPS
}
void osdResetConfig(osd_profile_t *osdProfile)
{
osdProfile->item_pos[OSD_RSSI_VALUE] = OSD_POS(22, 0) | VISIBLE_FLAG;
osdProfile->item_pos[OSD_MAIN_BATT_VOLTAGE] = OSD_POS(12, 0) | VISIBLE_FLAG;
osdProfile->item_pos[OSD_ARTIFICIAL_HORIZON] = OSD_POS(8, 6) | VISIBLE_FLAG;
osdProfile->item_pos[OSD_HORIZON_SIDEBARS] = OSD_POS(8, 6) | VISIBLE_FLAG;
osdProfile->item_pos[OSD_ONTIME] = OSD_POS(22, 11) | VISIBLE_FLAG;
osdProfile->item_pos[OSD_FLYTIME] = OSD_POS(22, 12) | VISIBLE_FLAG;
osdProfile->item_pos[OSD_FLYMODE] = OSD_POS(12, 11) | VISIBLE_FLAG;
osdProfile->item_pos[OSD_CRAFT_NAME] = OSD_POS(12, 12);
osdProfile->item_pos[OSD_THROTTLE_POS] = OSD_POS(1, 4);
osdProfile->item_pos[OSD_VTX_CHANNEL] = OSD_POS(8, 6);
osdProfile->item_pos[OSD_CURRENT_DRAW] = OSD_POS(1, 3);
osdProfile->item_pos[OSD_MAH_DRAWN] = OSD_POS(15, 3);
osdProfile->item_pos[OSD_GPS_SPEED] = OSD_POS(2, 2);
osdProfile->item_pos[OSD_GPS_SATS] = OSD_POS(2, 12);
osdProfile->item_pos[OSD_ALTITUDE] = OSD_POS(1, 5);
osdProfile->rssi_alarm = 20;
osdProfile->cap_alarm = 2200;
osdProfile->time_alarm = 10; // in minutes
osdProfile->alt_alarm = 100; // meters or feet depend on configuration
osdProfile->video_system = 0;
}
void osdInit(void)
{
char x, string_buffer[30];
armState = ARMING_FLAG(ARMED);
max7456Init(masterConfig.osdProfile.video_system);
max7456ClearScreen();
// display logo and help
x = 160;
for (int i = 1; i < 5; i++) {
for (int j = 3; j < 27; j++) {
if (x != 255)
max7456WriteChar(j, i, x++);
}
}
sprintf(string_buffer, "BF VERSION: %s", FC_VERSION_STRING);
max7456Write(5, 6, string_buffer);
#ifdef CMS
max7456Write(7, 7, CMS_STARTUP_HELP_TEXT1);
max7456Write(11, 8, CMS_STARTUP_HELP_TEXT2);
max7456Write(11, 9, CMS_STARTUP_HELP_TEXT3);
#endif
max7456RefreshAll();
refreshTimeout = 4 * REFRESH_1S;
osd7456DisplayPort = max7456DisplayPortInit();
#ifdef CMS
cmsDisplayPortRegister(osd7456DisplayPort);
#endif
}
void osdUpdateAlarms(void)
{
osd_profile_t *pOsdProfile = &masterConfig.osdProfile;
// This is overdone?
// uint16_t *itemPos = masterConfig.osdProfile.item_pos;
int32_t alt = osdGetAltitude(BaroAlt) / 100;
statRssi = rssi * 100 / 1024;
if (statRssi < pOsdProfile->rssi_alarm)
pOsdProfile->item_pos[OSD_RSSI_VALUE] |= BLINK_FLAG;
else
pOsdProfile->item_pos[OSD_RSSI_VALUE] &= ~BLINK_FLAG;
if (vbat <= (batteryWarningVoltage - 1))
pOsdProfile->item_pos[OSD_MAIN_BATT_VOLTAGE] |= BLINK_FLAG;
else
pOsdProfile->item_pos[OSD_MAIN_BATT_VOLTAGE] &= ~BLINK_FLAG;
if (STATE(GPS_FIX) == 0)
pOsdProfile->item_pos[OSD_GPS_SATS] |= BLINK_FLAG;
else
pOsdProfile->item_pos[OSD_GPS_SATS] &= ~BLINK_FLAG;
if (flyTime / 60 >= pOsdProfile->time_alarm && ARMING_FLAG(ARMED))
pOsdProfile->item_pos[OSD_FLYTIME] |= BLINK_FLAG;
else
pOsdProfile->item_pos[OSD_FLYTIME] &= ~BLINK_FLAG;
if (mAhDrawn >= pOsdProfile->cap_alarm)
pOsdProfile->item_pos[OSD_MAH_DRAWN] |= BLINK_FLAG;
else
pOsdProfile->item_pos[OSD_MAH_DRAWN] &= ~BLINK_FLAG;
if (alt >= pOsdProfile->alt_alarm)
pOsdProfile->item_pos[OSD_ALTITUDE] |= BLINK_FLAG;
else
pOsdProfile->item_pos[OSD_ALTITUDE] &= ~BLINK_FLAG;
}
void osdResetAlarms(void)
{
osd_profile_t *pOsdProfile = &masterConfig.osdProfile;
pOsdProfile->item_pos[OSD_RSSI_VALUE] &= ~BLINK_FLAG;
pOsdProfile->item_pos[OSD_MAIN_BATT_VOLTAGE] &= ~BLINK_FLAG;
pOsdProfile->item_pos[OSD_GPS_SATS] &= ~BLINK_FLAG;
pOsdProfile->item_pos[OSD_FLYTIME] &= ~BLINK_FLAG;
pOsdProfile->item_pos[OSD_MAH_DRAWN] &= ~BLINK_FLAG;
}
static void osdResetStats(void)
{
stats.max_current = 0;
stats.max_speed = 0;
stats.min_voltage = 500;
stats.max_current = 0;
stats.min_rssi = 99;
stats.max_altitude = 0;
}
static void osdUpdateStats(void)
{
int16_t value;
#ifdef GPS_notyet
value = GPS_speed * 36 / 1000;
if (stats.max_speed < value)
stats.max_speed = value;
#endif
if (stats.min_voltage > vbat)
stats.min_voltage = vbat;
value = amperage / 100;
if (stats.max_current < value)
stats.max_current = value;
if (stats.min_rssi > statRssi)
stats.min_rssi = statRssi;
if (stats.max_altitude < BaroAlt)
stats.max_altitude = BaroAlt;
}
static void osdShowStats(void)
{
uint8_t top = 2;
char buff[10];
max7456ClearScreen();
max7456Write(2, top++, " --- STATS ---");
if (STATE(GPS_FIX)) {
max7456Write(2, top, "MAX SPEED :");
itoa(stats.max_speed, buff, 10);
max7456Write(22, top++, buff);
}
max7456Write(2, top, "MIN BATTERY :");
sprintf(buff, "%d.%1dV", stats.min_voltage / 10, stats.min_voltage % 10);
max7456Write(22, top++, buff);
max7456Write(2, top, "MIN RSSI :");
itoa(stats.min_rssi, buff, 10);
strcat(buff, "%");
max7456Write(22, top++, buff);
if (feature(FEATURE_CURRENT_METER)) {
max7456Write(2, top, "MAX CURRENT :");
itoa(stats.max_current, buff, 10);
strcat(buff, "A");
max7456Write(22, top++, buff);
max7456Write(2, top, "USED MAH :");
itoa(mAhDrawn, buff, 10);
strcat(buff, "\x07");
max7456Write(22, top++, buff);
}
max7456Write(2, top, "MAX ALTITUDE :");
int32_t alt = osdGetAltitude(stats.max_altitude);
sprintf(buff, "%c%d.%01d%c", alt < 0 ? '-' : ' ', abs(alt / 100), abs((alt % 100) / 10), osdGetAltitudeSymbol());
max7456Write(22, top++, buff);
refreshTimeout = 60 * REFRESH_1S;
}
// called when motors armed
static void osdArmMotors(void)
{
max7456ClearScreen();
max7456Write(12, 7, "ARMED");
refreshTimeout = REFRESH_1S / 2;
osdResetStats();
}
static void osdRefresh(uint32_t currentTime)
{
static uint8_t lastSec = 0;
uint8_t sec;
// detect arm/disarm
if (armState != ARMING_FLAG(ARMED)) {
if (ARMING_FLAG(ARMED))
osdArmMotors(); // reset statistic etc
else
osdShowStats(); // show statistic
armState = ARMING_FLAG(ARMED);
}
osdUpdateStats();
sec = currentTime / 1000000;
if (ARMING_FLAG(ARMED) && sec != lastSec) {
flyTime++;
lastSec = sec;
}
if (refreshTimeout) {
if (IS_HI(THROTTLE) || IS_HI(PITCH)) // hide statistics
refreshTimeout = 1;
refreshTimeout--;
if (!refreshTimeout)
max7456ClearScreen();
return;
}
blinkState = (currentTime / 200000) % 2;
#ifdef CMS
if (!displayIsGrabbed(osd7456DisplayPort)) {
osdUpdateAlarms();
osdDrawElements();
#ifdef OSD_CALLS_CMS
} else {
cmsUpdate(currentTime);
#endif
}
#endif
}
/*
* Called periodically by the scheduler
*/
void osdUpdate(uint32_t currentTime)
{
static uint32_t counter = 0;
#ifdef MAX7456_DMA_CHANNEL_TX
// don't touch buffers if DMA transaction is in progress
if (max7456DmaInProgres())
return;
#endif // MAX7456_DMA_CHANNEL_TX
// redraw values in buffer
if (counter++ % 5 == 0)
osdRefresh(currentTime);
else // rest of time redraw screen 10 chars per idle to don't lock the main idle
max7456DrawScreen();
#ifdef CMS
// do not allow ARM if we are in menu
if (displayIsGrabbed(osd7456DisplayPort)) {
DISABLE_ARMING_FLAG(OK_TO_ARM);
}
#endif
}
#endif // OSD

69
src/main/io/osd.h Normal file
View file

@ -0,0 +1,69 @@
/*
* 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/>.
*/
#pragma once
#define VISIBLE_FLAG 0x0800
#define BLINK_FLAG 0x0400
#define VISIBLE(x) (x & VISIBLE_FLAG)
#define BLINK(x) ((x & BLINK_FLAG) && blinkState)
#define BLINK_OFF(x) (x & ~BLINK_FLAG)
typedef enum {
OSD_RSSI_VALUE,
OSD_MAIN_BATT_VOLTAGE,
OSD_CROSSHAIRS,
OSD_ARTIFICIAL_HORIZON,
OSD_HORIZON_SIDEBARS,
OSD_ONTIME,
OSD_FLYTIME,
OSD_FLYMODE,
OSD_CRAFT_NAME,
OSD_THROTTLE_POS,
OSD_VTX_CHANNEL,
OSD_CURRENT_DRAW,
OSD_MAH_DRAWN,
OSD_GPS_SPEED,
OSD_GPS_SATS,
OSD_ALTITUDE,
OSD_ITEM_COUNT // MUST BE LAST
} osd_items_e;
typedef enum {
OSD_UNIT_IMPERIAL,
OSD_UNIT_METRIC
} osd_unit_e;
typedef struct osd_profile_s {
uint16_t item_pos[OSD_ITEM_COUNT];
// Alarms
uint8_t rssi_alarm;
uint16_t cap_alarm;
uint16_t time_alarm;
uint16_t alt_alarm;
uint8_t video_system;
uint8_t row_shiftdown;
osd_unit_e units;
} osd_profile_t;
void osdInit(void);
void osdResetConfig(osd_profile_t *osdProfile);
void osdResetAlarms(void);
void osdUpdate(uint32_t currentTime);

View file

@ -65,6 +65,7 @@
#include "io/flashfs.h" #include "io/flashfs.h"
#include "io/beeper.h" #include "io/beeper.h"
#include "io/asyncfatfs/asyncfatfs.h" #include "io/asyncfatfs/asyncfatfs.h"
#include "io/osd.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "rx/spektrum.h" #include "rx/spektrum.h"
@ -219,7 +220,7 @@ static const char * const featureNames[] = {
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM", "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "UNUSED_2", "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "UNUSED_2",
"BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE", "BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE",
"SUPEREXPO", "VTX", "RX_SPI", "SOFTSPI", "PWM_SERVO_DRIVER", "PWM_OUTPUT_ENABLE", NULL "SUPEREXPO", "VTX", "RX_SPI", "SOFTSPI", "PWM_SERVO_DRIVER", "PWM_OUTPUT_ENABLE", "OSD", NULL
}; };
// sync this with rxFailsafeChannelMode_e // sync this with rxFailsafeChannelMode_e
@ -252,6 +253,14 @@ static const char * const *sensorHardwareNames[] = {gyroNames, accNames, baroNam
#endif #endif
#ifdef OSD
static const char * const lookupTableOsdType[] = {
"AUTO",
"PAL",
"NTSC"
};
#endif
typedef struct { typedef struct {
const char *name; const char *name;
#ifndef SKIP_CLI_COMMAND_HELP #ifndef SKIP_CLI_COMMAND_HELP
@ -518,6 +527,9 @@ typedef enum {
#ifdef ASYNC_GYRO_PROCESSING #ifdef ASYNC_GYRO_PROCESSING
TABLE_ASYNC_MODE, TABLE_ASYNC_MODE,
#endif #endif
#ifdef OSD
TABLE_OSD,
#endif
} lookupTableIndex_e; } lookupTableIndex_e;
static const lookupTableEntry_t lookupTables[] = { static const lookupTableEntry_t lookupTables[] = {
@ -553,6 +565,9 @@ static const lookupTableEntry_t lookupTables[] = {
#ifdef ASYNC_GYRO_PROCESSING #ifdef ASYNC_GYRO_PROCESSING
{ lookupTableAsyncMode, sizeof(lookupTableAsyncMode) / sizeof(char *) }, { lookupTableAsyncMode, sizeof(lookupTableAsyncMode) / sizeof(char *) },
#endif #endif
#ifdef OSD
{ lookupTableOsdType, sizeof(lookupTableOsdType) / sizeof(char *) },
#endif
}; };
#define VALUE_TYPE_OFFSET 0 #define VALUE_TYPE_OFFSET 0
@ -895,10 +910,35 @@ const clivalue_t valueTable[] = {
#ifdef LED_STRIP #ifdef LED_STRIP
{ "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.ledstrip_visual_beeper, .config.lookup = { TABLE_OFF_ON } }, { "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.ledstrip_visual_beeper, .config.lookup = { TABLE_OFF_ON } },
#endif #endif
{ "accgain_x", VAR_INT16 | MASTER_VALUE, &masterConfig.accGain.raw[X], .config.minmax = { 1, 8192 }, 0 }, { "accgain_x", VAR_INT16 | MASTER_VALUE, &masterConfig.accGain.raw[X], .config.minmax = { 1, 8192 }, 0 },
{ "accgain_y", VAR_INT16 | MASTER_VALUE, &masterConfig.accGain.raw[Y], .config.minmax = { 1, 8192 }, 0 }, { "accgain_y", VAR_INT16 | MASTER_VALUE, &masterConfig.accGain.raw[Y], .config.minmax = { 1, 8192 }, 0 },
{ "accgain_z", VAR_INT16 | MASTER_VALUE, &masterConfig.accGain.raw[Z], .config.minmax = { 1, 8192 }, 0 }, { "accgain_z", VAR_INT16 | MASTER_VALUE, &masterConfig.accGain.raw[Z], .config.minmax = { 1, 8192 }, 0 },
#ifdef OSD
{ "osd_video_system", VAR_UINT8 | MASTER_VALUE, &masterConfig.osdProfile.video_system, .config.minmax = { 0, 2 } },
{ "osd_row_shiftdown", VAR_UINT8 | MASTER_VALUE, &masterConfig.osdProfile.row_shiftdown, .config.minmax = { 0, 1 } },
{ "osd_units", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.osdProfile.units, .config.lookup = { TABLE_UNIT } },
{ "osd_rssi_alarm", VAR_UINT8 | MASTER_VALUE, &masterConfig.osdProfile.rssi_alarm, .config.minmax = { 0, 100 } },
{ "osd_cap_alarm", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.cap_alarm, .config.minmax = { 0, 20000 } },
{ "osd_time_alarm", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.time_alarm, .config.minmax = { 0, 60 } },
{ "osd_alt_alarm", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.alt_alarm, .config.minmax = { 0, 10000 } },
{ "osd_main_voltage_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE], .config.minmax = { 0, 65536 } },
{ "osd_rssi_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE], .config.minmax = { 0, 65536 } },
{ "osd_flytimer_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_FLYTIME], .config.minmax = { 0, 65536 } },
{ "osd_ontime_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ONTIME], .config.minmax = { 0, 65536 } },
{ "osd_flymode_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_FLYMODE], .config.minmax = { 0, 65536 } },
{ "osd_throttle_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS], .config.minmax = { 0, 65536 } },
{ "osd_vtx_channel_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_VTX_CHANNEL], .config.minmax = { 0, 65536 } },
{ "osd_crosshairs", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_CROSSHAIRS], .config.minmax = { 0, 65536 } },
{ "osd_artificial_horizon", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON], .config.minmax = { 0, 65536 } },
{ "osd_current_draw_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_CURRENT_DRAW], .config.minmax = { 0, 65536 } },
{ "osd_mah_drawn_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_MAH_DRAWN], .config.minmax = { 0, 65536 } },
{ "osd_craft_name_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_CRAFT_NAME], .config.minmax = { 0, 65536 } },
{ "osd_gps_speed_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_GPS_SPEED], .config.minmax = { 0, 65536 } },
{ "osd_gps_sats_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_GPS_SATS], .config.minmax = { 0, 65536 } },
{ "osd_altitude_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ALTITUDE], .config.minmax = { 0, 65536 } },
#endif
}; };
#define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t)) #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))

View file

@ -220,6 +220,8 @@
#define MSP_OSD_VIDEO_CONFIG 180 #define MSP_OSD_VIDEO_CONFIG 180
#define MSP_SET_OSD_VIDEO_CONFIG 181 #define MSP_SET_OSD_VIDEO_CONFIG 181
#define MSP_DISPLAYPORT 182
// //
// Multwii original MSP commands // Multwii original MSP commands
// //

View file

@ -81,6 +81,12 @@ typedef enum {
#ifdef STACK_CHECK #ifdef STACK_CHECK
TASK_STACK_CHECK, TASK_STACK_CHECK,
#endif #endif
#ifdef OSD
TASK_OSD,
#endif
#ifdef CMS
TASK_CMS,
#endif
/* Count of real tasks */ /* Count of real tasks */
TASK_COUNT, TASK_COUNT,

View file

@ -207,3 +207,18 @@
#define USABLE_TIMER_CHANNEL_COUNT 7 // 6 Outputs; PPM; #define USABLE_TIMER_CHANNEL_COUNT 7 // 6 Outputs; PPM;
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15)) #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15))
#define OSD
// include the max7456 driver
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI1
#define MAX7456_SPI_CS_PIN PB1
#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD*2)
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
//#define MAX7456_DMA_CHANNEL_TX DMA1_Channel3
//#define MAX7456_DMA_CHANNEL_RX DMA1_Channel2
//#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_CH3_HANDLER
//#define USE_MSP_DISPLAYPORT
#define CMS

View file

@ -14,4 +14,17 @@ TARGET_SRC = \
drivers/compass_mag3110.c \ drivers/compass_mag3110.c \
drivers/light_ws2811strip.c \ drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f30x.c \ drivers/light_ws2811strip_stm32f30x.c \
drivers/serial_usb_vcp.c drivers/serial_usb_vcp.c \
drivers/max7456.c \
drivers/display.c \
io/osd.c \
io/displayport_max7456.c \
io/displayport_msp.c \
io/displayport_oled.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_misc.c \
cms/cms_menu_osd.c