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

Code tidy and addition of GPL headers

This commit is contained in:
Martin Budden 2016-11-06 08:01:34 +00:00
parent 31b6e7e024
commit a7a428a5bb
41 changed files with 424 additions and 180 deletions

View file

@ -560,10 +560,19 @@ HIGHEND_SRC = \
flight/gtune.c \
flight/navigation.c \
flight/gps_conversion.c \
io/gps.c \
io/ledstrip.c \
io/canvas.c \
io/cms.c \
io/cms_builtin.c \
io/cms_imu.c \
io/cms_blackbox.c \
io/cms_vtx.c \
io/cms_ledstrip.c \
io/displayport_oled.c \
io/dashboard.c \
io/gps.c \
io/ledstrip.c \
io/osd.c \
io/osd_max7456.c \
sensors/sonar.c \
sensors/barometer.c \
telemetry/telemetry.c \

View file

@ -35,16 +35,25 @@ void displayOpen(displayPort_t *instance)
{
instance->vTable->open(instance);
instance->vTable->clear(instance);
instance->inCMS = true;
instance->isOpen = true;
}
void displayClose(displayPort_t *instance)
{
instance->vTable->close(instance);
instance->inCMS = false;
instance->isOpen = false;
}
int displayWrite(displayPort_t *instance, uint8_t x, uint8_t y, char *s)
bool displayIsOpen(const displayPort_t *instance)
{
if (instance && instance->isOpen) { // can be called before initialised
return true;
} else {
return false;
}
}
int displayWrite(displayPort_t *instance, uint8_t x, uint8_t y, const char *s)
{
return instance->vTable->write(instance, x, y, s);
}
@ -59,7 +68,7 @@ void displayResync(displayPort_t *instance)
instance->vTable->resync(instance);
}
uint16_t displayTxBytesFree(displayPort_t *instance)
uint16_t displayTxBytesFree(const displayPort_t *instance)
{
return instance->vTable->txBytesFree(instance);
}

View file

@ -26,23 +26,24 @@ typedef struct displayPort_s {
// CMS state
bool cleared;
int8_t cursorRow;
bool inCMS;
bool isOpen;
} displayPort_t;
typedef struct displayPortVTable_s {
int (*open)(displayPort_t *displayPort);
int (*close)(displayPort_t *displayPort);
int (*clear)(displayPort_t *displayPort);
int (*write)(displayPort_t *displayPort, uint8_t col, uint8_t row, char *text);
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)(displayPort_t *displayPort);
uint32_t (*txBytesFree)(const displayPort_t *displayPort);
} displayPortVTable_t;
void displayOpen(displayPort_t *instance);
void displayClose(displayPort_t *instance);
bool displayIsOpen(const displayPort_t *instance);
void displayClear(displayPort_t *instance);
int displayWrite(displayPort_t *instance, uint8_t x, uint8_t y, char *s);
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(displayPort_t *instance);
uint16_t displayTxBytesFree(const displayPort_t *instance);

View file

@ -294,7 +294,7 @@ void max7456WriteChar(uint8_t x, uint8_t y, uint8_t c)
screenBuffer[y*30+x] = c;
}
void max7456Write(uint8_t x, uint8_t y, char *buff)
void max7456Write(uint8_t x, uint8_t y, const char *buff)
{
uint8_t i = 0;
for (i = 0; *(buff+i); i++)
@ -387,7 +387,7 @@ void max7456RefreshAll(void)
}
}
void max7456WriteNvm(uint8_t char_address, uint8_t *font_data)
void max7456WriteNvm(uint8_t char_address, const uint8_t *font_data)
{
uint8_t x;

View file

@ -146,9 +146,9 @@ extern uint16_t maxScreenSize;
void max7456Init(uint8_t system);
void max7456DrawScreen(void);
void max7456WriteNvm(uint8_t char_address, uint8_t *font_data);
void max7456WriteNvm(uint8_t char_address, const uint8_t *font_data);
uint8_t max7456GetRowsCount(void);
void max7456Write(uint8_t x, uint8_t y, char *buff);
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);

View file

@ -1010,7 +1010,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
sbufWriteU16(dst, masterConfig.osdProfile.time_alarm);
sbufWriteU16(dst, masterConfig.osdProfile.alt_alarm);
for (i = 0; i < OSD_MAX_ITEMS; i++) {
for (i = 0; i < OSD_ITEM_COUNT; i++) {
sbufWriteU16(dst, masterConfig.osdProfile.item_pos[i]);
}
#else

View file

@ -40,13 +40,11 @@
#include "flight/pid.h"
#include "flight/altitudehold.h"
#include "io/cms.h"
#include "io/beeper.h"
#include "io/cms.h"
#include "io/dashboard.h"
#include "io/gps.h"
#include "io/ledstrip.h"
#include "io/cms.h"
#include "io/osd.h"
#include "io/serial.h"
#include "io/serial_cli.h"

View file

@ -40,8 +40,6 @@
#include "fc/rc_curves.h"
#include "fc/runtime_config.h"
#include "io/cms.h"
#include "io/gps.h"
#include "io/beeper.h"
#include "io/motors.h"

View file

@ -1,3 +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/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
@ -22,47 +39,47 @@
static displayPort_t canvasDisplayPort;
static int canvasOutput(displayPort_t *displayPort, uint8_t cmd, uint8_t *buf, int len)
static int canvasOutput(displayPort_t *displayPort, uint8_t cmd, const uint8_t *buf, int len)
{
UNUSED(displayPort);
mspSerialPush(cmd, buf, len);
return 6 + len;
return mspSerialPush(cmd, buf, len);
}
static int canvasBegin(displayPort_t *displayPort)
static int canvasOpen(displayPort_t *displayPort)
{
uint8_t subcmd[] = { 0 };
const uint8_t subcmd[] = { 0 };
return canvasOutput(displayPort, MSP_CANVAS, subcmd, sizeof(subcmd));
}
static int canvasHeartBeat(displayPort_t *displayPort)
{
return canvasBegin(displayPort);
return canvasOpen(displayPort);
}
static int canvasEnd(displayPort_t *displayPort)
static int canvasClose(displayPort_t *displayPort)
{
uint8_t subcmd[] = { 1 };
const uint8_t subcmd[] = { 1 };
return canvasOutput(displayPort, MSP_CANVAS, subcmd, sizeof(subcmd));
}
static int canvasClear(displayPort_t *displayPort)
{
uint8_t subcmd[] = { 2 };
const uint8_t subcmd[] = { 2 };
return canvasOutput(displayPort, MSP_CANVAS, subcmd, sizeof(subcmd));
}
static int canvasWrite(displayPort_t *displayPort, uint8_t col, uint8_t row, char *string)
static int canvasWrite(displayPort_t *displayPort, uint8_t col, uint8_t row, const char *string)
{
int len;
uint8_t buf[30 + 4];
#define MSP_CANVAS_MAX_STRING_LENGTH 30
uint8_t buf[MSP_CANVAS_MAX_STRING_LENGTH + 4];
if ((len = strlen(string)) >= 30)
len = 30;
int len = strlen(string);
if (len >= MSP_CANVAS_MAX_STRING_LENGTH) {
len = MSP_CANVAS_MAX_STRING_LENGTH;
}
buf[0] = 3;
buf[1] = row;
@ -79,27 +96,27 @@ static void canvasResync(displayPort_t *displayPort)
displayPort->cols = 30;
}
static uint32_t canvasTxBytesFree(displayPort_t *displayPort)
static uint32_t canvasTxBytesFree(const displayPort_t *displayPort)
{
UNUSED(displayPort);
return mspSerialTxBytesFree();
}
static const displayPortVTable_t canvasVTable = {
canvasBegin,
canvasEnd,
canvasClear,
canvasWrite,
canvasHeartBeat,
canvasResync,
canvasTxBytesFree,
.open = canvasOpen,
.close = canvasClose,
.clear = canvasClear,
.write = canvasWrite,
.heartbeat = canvasHeartBeat,
.resync = canvasResync,
.txBytesFree = canvasTxBytesFree
};
void canvasInit()
displayPort_t *canvasInit(void)
{
canvasDisplayPort.vTable = &canvasVTable;
canvasDisplayPort.inCMS = false;
canvasDisplayPort.isOpen = false;
canvasResync(&canvasDisplayPort);
cmsDisplayPortRegister(&canvasDisplayPort);
return &canvasDisplayPort;
}
#endif

View file

@ -1,3 +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
void canvasInit(void);
void canvasCmsInit(displayPort_t *dPort);
struct displayPort_s;
struct displayPort_s *canvasInit(void);

View file

@ -1,3 +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/>.
*/
//
// CMS things for blackbox and flashfs.
//

View file

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

@ -1,3 +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/>.
*/
//
// Built-in menu contents and support functions
//

View file

@ -1 +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 menuMain;

View file

@ -1,3 +1,19 @@
/*
* 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.

View file

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

@ -1,3 +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/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>

View file

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

@ -1,2 +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;

View file

@ -1,3 +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/>.
*/
//
// Menu element types
// XXX Upon separation, all OME would be renamed to CME_ or similar.

View file

@ -1,3 +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/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <ctype.h>

View file

@ -1 +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;

View file

@ -83,6 +83,7 @@ static uint32_t nextDisplayUpdateAt = 0;
static bool dashboardPresent = false;
static rxConfig_t *rxConfig;
static displayPort_t *displayPort;
#define PAGE_TITLE_LINE_COUNT 1
@ -588,7 +589,7 @@ void dashboardUpdate(uint32_t currentTime)
static uint8_t previousArmedState = 0;
#ifdef OLEDCMS
if (oledDisplayPort.inCMS) {
if (displayIsOpen(displayPort)) {
return;
}
#endif
@ -704,8 +705,9 @@ void dashboardInit(rxConfig_t *rxConfigToUse)
resetDisplay();
delay(200);
displayPort = displayPortOledInit();
#if defined(CMS) && defined(OLEDCMS)
displayPortOledInit();
cmsDisplayPortRegister(displayPort);
#endif
rxConfig = rxConfigToUse;

View file

@ -20,18 +20,12 @@
#include "platform.h"
#ifdef OLEDCMS
#include "common/utils.h"
#include "drivers/display.h"
#include "drivers/display_ug2864hsweg01.h"
#include "io/cms.h"
#include "io/displayport_oled.h"
// Exported
displayPort_t oledDisplayPort;
static displayPort_t oledDisplayPort;
static int oledOpen(displayPort_t *displayPort)
{
@ -52,7 +46,7 @@ static int oledClear(displayPort_t *displayPort)
return 0;
}
static int oledWrite(displayPort_t *displayPort, uint8_t x, uint8_t y, char *s)
static int oledWrite(displayPort_t *displayPort, uint8_t x, uint8_t y, const char *s)
{
UNUSED(displayPort);
i2c_OLED_set_xy(x, y);
@ -71,7 +65,7 @@ static void oledResync(displayPort_t *displayPort)
UNUSED(displayPort);
}
static uint32_t oledTxBytesFree(displayPort_t *displayPort)
static uint32_t oledTxBytesFree(const displayPort_t *displayPort)
{
UNUSED(displayPort);
return UINT32_MAX;
@ -87,13 +81,11 @@ static const displayPortVTable_t oledVTable = {
.txBytesFree = oledTxBytesFree
};
void displayPortOledInit()
displayPort_t *displayPortOledInit(void)
{
oledDisplayPort.vTable = &oledVTable;
oledDisplayPort.rows = SCREEN_CHARACTER_ROW_COUNT;
oledDisplayPort.cols = SCREEN_CHARACTER_COLUMN_COUNT;
oledDisplayPort.inCMS = false;
cmsDisplayPortRegister(&oledDisplayPort);
oledDisplayPort.isOpen = false;
return &oledDisplayPort;
}
#endif // OLEDCMS

View file

@ -17,6 +17,4 @@
#pragma once
void displayPortOledInit(void);
extern displayPort_t oledDisplayPort;
displayPort_t *displayPortOledInit(void);

View file

@ -38,8 +38,6 @@
#include "sensors/sensors.h"
#include "io/cms.h"
#include "io/serial.h"
#include "io/dashboard.h"
#include "io/gps.h"

View file

@ -74,14 +74,24 @@ bool blinkState = true;
//extern uint8_t RSSI; // TODO: not used?
static uint16_t flyTime = 0;
uint8_t statRssi;
static uint8_t statRssi;
statistic_t stats;
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
uint8_t armState;
static uint8_t armState;
static displayPort_t *osd7456DisplayPort;
// OSD forwards
@ -109,7 +119,7 @@ void osdDrawElements(void)
;
#endif
#ifdef CMS
else if (sensors(SENSOR_ACC) || osd7456DisplayPort.inCMS)
else if (sensors(SENSOR_ACC) || displayIsOpen(osd7456DisplayPort))
#else
else if (sensors(SENSOR_ACC))
#endif
@ -132,7 +142,7 @@ void osdDrawElements(void)
#ifdef GPS
#ifdef CMS
if (sensors(SENSOR_GPS) || osd7456DisplayPort.inCMS)
if (sensors(SENSOR_GPS) || displayIsOpen(osd7456DisplayPort))
#else
if (sensors(SENSOR_GPS))
#endif
@ -406,8 +416,9 @@ void osdInit(void)
refreshTimeout = 4 * REFRESH_1S;
osd7456DisplayPort = osd7456DisplayPortInit();
#ifdef CMS
osd7456DisplayPortInit();
cmsDisplayPortRegister(osd7456DisplayPort);
#endif
}
@ -584,8 +595,9 @@ void updateOsd(uint32_t currentTime)
#ifdef CMS
// do not allow ARM if we are in menu
if (osd7456DisplayPort.inCMS)
if (displayIsOpen(osd7456DisplayPort)) {
DISABLE_ARMING_FLAG(OK_TO_ARM);
}
#endif
}
@ -632,7 +644,7 @@ void osdUpdate(uint32_t currentTime)
blinkState = (millis() / 200) % 2;
#ifdef CMS
if (!osd7456DisplayPort.inCMS) {
if (!displayIsOpen(osd7456DisplayPort)) {
osdUpdateAlarms();
osdDrawElements();
#ifdef OSD_CALLS_CMS

View file

@ -34,16 +34,16 @@ typedef enum {
OSD_GPS_SPEED,
OSD_GPS_SATS,
OSD_ALTITUDE,
OSD_MAX_ITEMS, // MUST BE LAST
} osd_items_t;
OSD_ITEM_COUNT // MUST BE LAST
} osd_items_e;
typedef enum {
OSD_UNIT_IMPERIAL,
OSD_UNIT_METRIC
} osd_unit_t;
} osd_unit_e;
typedef struct {
uint16_t item_pos[OSD_MAX_ITEMS];
typedef struct osd_profile_s {
uint16_t item_pos[OSD_ITEM_COUNT];
// Alarms
uint8_t rssi_alarm;
@ -54,26 +54,14 @@ typedef struct {
uint8_t video_system;
uint8_t row_shiftdown;
osd_unit_t units;
osd_unit_e units;
} osd_profile_t;
typedef struct {
int16_t max_speed;
int16_t min_voltage; // /10
int16_t max_current; // /10
int16_t min_rssi;
int16_t max_altitude;
} statistic_t;
void updateOsd(uint32_t currentTime);
void osdInit(void);
void resetOsdConfig(osd_profile_t *osdProfile);
void osdResetAlarms(void);
#ifdef CMS
void osdCmsInit(displayPort_t *);
#endif
// Character coordinate and attributes
#define OSD_POS(x,y) (x | (y << 5))

View file

@ -1,3 +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/>.
*/
#include <stdbool.h>
#include <stdint.h>
@ -16,20 +33,20 @@ displayPort_t osd7456DisplayPort; // Referenced from osd.c
extern uint16_t refreshTimeout;
static int osdMenuBegin(displayPort_t *displayPort)
static int osdMenuOpen(displayPort_t *displayPort)
{
UNUSED(displayPort);
osdResetAlarms();
displayPort->inCMS = true;
displayPort->isOpen = true;
refreshTimeout = 0;
return 0;
}
static int osdMenuEnd(displayPort_t *displayPort)
static int osdMenuClose(displayPort_t *displayPort)
{
UNUSED(displayPort);
displayPort->inCMS = false;
displayPort->isOpen = false;
return 0;
}
@ -42,7 +59,7 @@ static int osdClearScreen(displayPort_t *displayPort)
return 0;
}
static int osdWrite(displayPort_t *displayPort, uint8_t x, uint8_t y, char *s)
static int osdWrite(displayPort_t *displayPort, uint8_t x, uint8_t y, const char *s)
{
UNUSED(displayPort);
max7456Write(x, y, s);
@ -64,27 +81,27 @@ static int osdHeartbeat(displayPort_t *displayPort)
return 0;
}
static uint32_t osdTxBytesFree(displayPort_t *displayPort)
static uint32_t osdTxBytesFree(const displayPort_t *displayPort)
{
UNUSED(displayPort);
return UINT32_MAX;
}
static displayPortVTable_t osdVTable = {
osdMenuBegin,
osdMenuEnd,
osdClearScreen,
osdWrite,
osdHeartbeat,
osdResync,
osdTxBytesFree,
.open = osdMenuOpen,
.close = osdMenuClose,
.clear = osdClearScreen,
.write = osdWrite,
.heartbeat = osdHeartbeat,
.resync = osdResync,
.txBytesFree = osdTxBytesFree,
};
void osd7456DisplayPortInit(void)
displayPort_t *osd7456DisplayPortInit(void)
{
osd7456DisplayPort.vTable = &osdVTable;
osd7456DisplayPort.inCMS = false;
osd7456DisplayPort.isOpen = false;
osdResync(&osd7456DisplayPort);
cmsDisplayPortRegister(&osd7456DisplayPort);
return &osd7456DisplayPort;
}
#endif // OSD

View file

@ -1,5 +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 displayPort_t osd7456DisplayPort;
void osd7456DisplayPortInit(void);
displayPort_t *osd7456DisplayPortInit(void);

View file

@ -945,7 +945,7 @@ const clivalue_t valueTable[] = {
#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_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 } },

View file

@ -463,7 +463,7 @@ void init(void)
#ifdef CANVAS
if (feature(FEATURE_CANVAS)) {
canvasInit();
cmsDisplayPortRegister(canvasInit());
}
#endif

View file

@ -35,4 +35,3 @@ typedef struct mspPacket_s {
struct serialPort_s;
typedef void (*mspPostProcessFnPtr)(struct serialPort_s *port); // msp post process function, used for gracefully handling reboots, etc.
typedef mspResult_e (*mspProcessCommandFnPtr)(mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn);
typedef void (*mspPushCommandFnPtr)(mspPacket_t *push, uint8_t *, int);

View file

@ -120,7 +120,7 @@ static uint8_t mspSerialChecksumBuf(uint8_t checksum, const uint8_t *data, int l
#define JUMBO_FRAME_SIZE_LIMIT 255
static void mspSerialEncode(mspPort_t *msp, mspPacket_t *packet)
static int mspSerialEncode(mspPort_t *msp, mspPacket_t *packet)
{
serialBeginWrite(msp->port);
const int len = sbufBytesRemaining(&packet->buf);
@ -140,6 +140,7 @@ static void mspSerialEncode(mspPort_t *msp, mspPacket_t *packet)
}
serialWrite(msp->port, checksum);
serialEndWrite(msp->port);
return sizeof(hdr) + len + 1; // header, data, and checksum
}
static mspPostProcessFnPtr mspSerialProcessReceivedCommand(mspPort_t *msp, mspProcessCommandFnPtr mspProcessCommandFn)
@ -211,9 +212,10 @@ void mspSerialInit(void)
mspSerialAllocatePorts();
}
void mspSerialPush(uint8_t cmd, uint8_t *data, int datalen)
int mspSerialPush(uint8_t cmd, const uint8_t *data, int datalen)
{
static uint8_t pushBuf[30];
int ret = 0;
mspPacket_t push = {
.buf = { .ptr = pushBuf, .end = ARRAYEND(pushBuf), },
@ -221,7 +223,7 @@ void mspSerialPush(uint8_t cmd, uint8_t *data, int datalen)
.result = 0,
};
for (uint8_t portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
for (int portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
mspPort_t * const mspPort = &mspPorts[portIndex];
if (!mspPort->port) {
continue;
@ -236,15 +238,16 @@ void mspSerialPush(uint8_t cmd, uint8_t *data, int datalen)
sbufSwitchToReader(&push.buf, pushBuf);
mspSerialEncode(mspPort, &push);
ret = mspSerialEncode(mspPort, &push);
}
return ret; // return the number of bytes written
}
uint32_t mspSerialTxBytesFree()
{
uint32_t minroom = UINT16_MAX;
uint32_t ret = UINT32_MAX;
for (uint8_t portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
for (int portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
mspPort_t * const mspPort = &mspPorts[portIndex];
if (!mspPort->port) {
continue;
@ -255,12 +258,11 @@ uint32_t mspSerialTxBytesFree()
continue;
}
uint32_t room = serialTxBytesFree(mspPort->port);
if (room < minroom) {
minroom = room;
const uint32_t bytesFree = serialTxBytesFree(mspPort->port);
if (bytesFree < ret) {
ret = bytesFree;
}
}
return minroom;
return ret;
}

View file

@ -66,5 +66,5 @@ void mspSerialInit(void);
void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData, mspProcessCommandFnPtr mspProcessCommandFn);
void mspSerialAllocatePorts(void);
void mspSerialReleasePortIfAllocated(struct serialPort_s *serialPort);
void mspSerialPush(uint8_t cmd, uint8_t *data, int datalen);
int mspSerialPush(uint8_t cmd, const uint8_t *data, int datalen);
uint32_t mspSerialTxBytesFree(void);

View file

@ -1,4 +1,3 @@
#define USE_DPRINTF
/*
* This file is part of Cleanflight.
*

View file

@ -9,17 +9,8 @@ TARGET_SRC = \
drivers/compass_ak8963.c \
drivers/compass_ak8975.c \
drivers/compass_hmc5883l.c \
drivers/max7456.c \
drivers/serial_usb_vcp.c \
drivers/transponder_ir.c \
drivers/transponder_ir_stm32f30x.c \
io/transponder_ir.c \
drivers/max7456.c \
io/osd.c \
io/osd_max7456.c \
io/canvas.c \
io/cms.c \
io/cms_builtin.c \
io/cms_imu.c \
io/cms_blackbox.c \
io/cms_vtx.c \
io/cms_ledstrip.c
io/transponder_ir.c

View file

@ -5,13 +5,5 @@ TARGET_SRC = \
drivers/accgyro_spi_mpu6000.c \
drivers/barometer_ms5611.c \
drivers/compass_hmc5883l.c \
drivers/max7456.c \
io/osd.c \
io/osd_max7456.c \
io/cms.c \
io/cms_builtin.c \
io/cms_imu.c \
io/cms_blackbox.c \
io/cms_ledstrip.c \
io/canvas.c
drivers/max7456.c

View file

@ -11,13 +11,4 @@ TARGET_SRC = \
drivers/compass_hmc5883l.c \
drivers/flash_m25p16.c \
drivers/vtx_soft_spi_rtc6705.c \
drivers/max7456.c \
io/osd.c \
io/osd_max7456.c \
io/canvas.c \
io/cms.c \
io/cms_builtin.c \
io/cms_imu.c \
io/cms_blackbox.c \
io/cms_vtx.c \
io/cms_ledstrip.c
drivers/max7456.c

View file

@ -8,12 +8,5 @@ TARGET_SRC = \
drivers/barometer_bmp085.c \
drivers/barometer_bmp280.c \
drivers/compass_ak8975.c \
drivers/compass_hmc5883l.c \
io/canvas.c \
io/cms.c \
io/cms_builtin.c \
io/cms_imu.c \
io/cms_blackbox.c \
io/cms_vtx.c \
io/cms_ledstrip.c
drivers/compass_hmc5883l.c

View file

@ -25,14 +25,4 @@ TARGET_SRC = \
drivers/compass_ak8975.c \
drivers/compass_hmc5883l.c \
drivers/flash_m25p16.c \
drivers/max7456.c \
io/osd.c \
io/osd_max7456.c \
io/canvas.c \
io/cms.c \
io/cms_builtin.c \
io/cms_imu.c \
io/cms_blackbox.c \
io/cms_vtx.c \
io/cms_ledstrip.c
drivers/max7456.c