mirror of
https://github.com/opentx/opentx.git
synced 2025-07-15 04:15:26 +03:00
[X12S] GPS now OK
This commit is contained in:
parent
91dc936ef3
commit
10aefb10db
48 changed files with 730 additions and 436 deletions
|
@ -907,11 +907,16 @@ enum MixSources {
|
|||
#if defined(CPUARM)
|
||||
MIXSRC_TX_VOLTAGE, LUA_EXPORT("tx-voltage", "Transmitter battery voltage [volts]")
|
||||
MIXSRC_TX_TIME, LUA_EXPORT("clock", "RTC clock [minutes from midnight]")
|
||||
MIXSRC_RESERVE1,
|
||||
#if defined(INTERNAL_GPS)
|
||||
MIXSRC_TX_GPS,
|
||||
MIXSRC_FIRST_RESERVE,
|
||||
#else
|
||||
MIXSRC_FIRST_RESERVE,
|
||||
MIXSRC_RESERVE2,
|
||||
#endif
|
||||
MIXSRC_RESERVE3,
|
||||
MIXSRC_RESERVE4,
|
||||
MIXSRC_RESERVE5,
|
||||
MIXSRC_LAST_RESERVE,
|
||||
MIXSRC_FIRST_TIMER,
|
||||
MIXSRC_TIMER1 = MIXSRC_FIRST_TIMER, LUA_EXPORT("timer1", "Timer 1 value [seconds]")
|
||||
MIXSRC_TIMER2, LUA_EXPORT("timer2", "Timer 2 value [seconds]")
|
||||
|
|
257
radio/src/gps.cpp
Normal file
257
radio/src/gps.cpp
Normal file
|
@ -0,0 +1,257 @@
|
|||
/*
|
||||
* 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 "opentx.h"
|
||||
#include <ctype.h>
|
||||
|
||||
gpsdata_t gpsData;
|
||||
|
||||
/* This is a light implementation of a GPS frame decoding
|
||||
This should work with most of modern GPS devices configured to output 5 frames.
|
||||
It assumes there are some NMEA GGA frames to decode on the serial bus
|
||||
Now verifies checksum correctly before applying data
|
||||
|
||||
Here we use only the following data :
|
||||
- latitude
|
||||
- longitude
|
||||
- GPS fix is/is not ok
|
||||
- GPS num sat (4 is enough to be +/- reliable)
|
||||
// added by Mis
|
||||
- GPS altitude (for OSD displaying)
|
||||
- GPS speed (for OSD displaying)
|
||||
*/
|
||||
|
||||
#define NO_FRAME 0
|
||||
#define FRAME_GGA 1
|
||||
#define FRAME_RMC 2
|
||||
|
||||
#define DIGIT_TO_VAL(_x) (_x - '0')
|
||||
|
||||
uint32_t GPS_coord_to_degrees(const char * coordinateString)
|
||||
{
|
||||
const char * fieldSeparator, * remainingString;
|
||||
uint8_t degrees = 0, minutes = 0;
|
||||
uint16_t fractionalMinutes = 0;
|
||||
uint8_t digitIndex;
|
||||
|
||||
// scan for decimal point or end of field
|
||||
for (fieldSeparator = coordinateString; isdigit((unsigned char) *fieldSeparator); fieldSeparator++) {
|
||||
if (fieldSeparator >= coordinateString + 15)
|
||||
return 0; // stop potential fail
|
||||
}
|
||||
remainingString = coordinateString;
|
||||
|
||||
// convert degrees
|
||||
while ((fieldSeparator - remainingString) > 2) {
|
||||
if (degrees)
|
||||
degrees *= 10;
|
||||
degrees += DIGIT_TO_VAL(*remainingString++);
|
||||
}
|
||||
// convert minutes
|
||||
while (fieldSeparator > remainingString) {
|
||||
if (minutes)
|
||||
minutes *= 10;
|
||||
minutes += DIGIT_TO_VAL(*remainingString++);
|
||||
}
|
||||
// convert fractional minutes
|
||||
// expect up to four digits, result is in
|
||||
// ten-thousandths of a minute
|
||||
if (*fieldSeparator == '.') {
|
||||
remainingString = fieldSeparator + 1;
|
||||
for (digitIndex = 0; digitIndex < 4; digitIndex++) {
|
||||
fractionalMinutes *= 10;
|
||||
if (isdigit((unsigned char) *remainingString))
|
||||
fractionalMinutes += *remainingString++ - '0';
|
||||
}
|
||||
}
|
||||
// TODO return degrees * 10000000UL + (minutes * 1000000UL + fractionalMinutes * 100UL) / 6;
|
||||
return degrees * 1000000UL + (minutes * 100000UL + fractionalMinutes * 10UL) / 6;
|
||||
}
|
||||
|
||||
// helper functions
|
||||
uint32_t grab_fields(char * src, uint8_t mult)
|
||||
{
|
||||
uint32_t i;
|
||||
uint32_t tmp = 0;
|
||||
for (i = 0; src[i] != 0; i++) {
|
||||
if (src[i] == '.') {
|
||||
i++;
|
||||
if (mult == 0)
|
||||
break;
|
||||
else
|
||||
src[i + mult] = 0;
|
||||
}
|
||||
tmp *= 10;
|
||||
if (src[i] >= '0' && src[i] <= '9')
|
||||
tmp += src[i] - '0';
|
||||
if (i >= 15)
|
||||
return 0; // out of bounds
|
||||
}
|
||||
return tmp;
|
||||
}
|
||||
|
||||
typedef struct gpsDataNmea_s
|
||||
{
|
||||
uint8_t fix;
|
||||
int32_t latitude;
|
||||
int32_t longitude;
|
||||
uint8_t numSat;
|
||||
uint16_t altitude;
|
||||
uint16_t speed;
|
||||
uint16_t groundCourse;
|
||||
} gpsDataNmea_t;
|
||||
|
||||
bool gpsNewFrameNMEA(char c)
|
||||
{
|
||||
static gpsDataNmea_t gps_Msg;
|
||||
|
||||
uint8_t frameOK = 0;
|
||||
static uint8_t param = 0, offset = 0, parity = 0;
|
||||
static char string[15];
|
||||
static uint8_t checksum_param, gps_frame = NO_FRAME;
|
||||
|
||||
switch (c) {
|
||||
case '$':
|
||||
param = 0;
|
||||
offset = 0;
|
||||
parity = 0;
|
||||
break;
|
||||
case ',':
|
||||
case '*':
|
||||
string[offset] = 0;
|
||||
if (param == 0) {
|
||||
// Frame identification
|
||||
gps_frame = NO_FRAME;
|
||||
if (string[0] == 'G' && string[1] == 'P' && string[2] == 'G' && string[3] == 'G' && string[4] == 'A')
|
||||
gps_frame = FRAME_GGA;
|
||||
if (string[0] == 'G' && string[1] == 'P' && string[2] == 'R' && string[3] == 'M' && string[4] == 'C')
|
||||
gps_frame = FRAME_RMC;
|
||||
}
|
||||
|
||||
switch (gps_frame) {
|
||||
case FRAME_GGA: //************* GPGGA FRAME parsing
|
||||
switch (param) {
|
||||
// case 1: // Time information
|
||||
// break;
|
||||
case 2:
|
||||
gps_Msg.latitude = GPS_coord_to_degrees(string);
|
||||
break;
|
||||
case 3:
|
||||
if (string[0] == 'S')
|
||||
gps_Msg.latitude *= -1;
|
||||
break;
|
||||
case 4:
|
||||
gps_Msg.longitude = GPS_coord_to_degrees(string);
|
||||
break;
|
||||
case 5:
|
||||
if (string[0] == 'W')
|
||||
gps_Msg.longitude *= -1;
|
||||
break;
|
||||
case 6:
|
||||
if (string[0] > '0') {
|
||||
gps_Msg.fix = 1;
|
||||
}
|
||||
else {
|
||||
gps_Msg.fix = 0;
|
||||
}
|
||||
break;
|
||||
case 7:
|
||||
gps_Msg.numSat = grab_fields(string, 0);
|
||||
break;
|
||||
case 9:
|
||||
gps_Msg.altitude = grab_fields(string, 0); // altitude in meters added by Mis
|
||||
break;
|
||||
}
|
||||
break;
|
||||
case FRAME_RMC: //************* GPRMC FRAME parsing
|
||||
switch (param) {
|
||||
case 7:
|
||||
gps_Msg.speed = ((grab_fields(string, 1) * 5144L) / 1000L); // speed in cm/s added by Mis
|
||||
break;
|
||||
case 8:
|
||||
gps_Msg.groundCourse = (grab_fields(string, 1)); // ground course deg * 10
|
||||
break;
|
||||
}
|
||||
break;
|
||||
|
||||
}
|
||||
|
||||
param++;
|
||||
offset = 0;
|
||||
if (c == '*')
|
||||
checksum_param = 1;
|
||||
else
|
||||
parity ^= c;
|
||||
break;
|
||||
case '\r':
|
||||
case '\n':
|
||||
if (checksum_param) { //parity checksum
|
||||
uint8_t checksum = 16 * ((string[0] >= 'A') ? string[0] - 'A' + 10 : string[0] - '0') +
|
||||
((string[1] >= 'A') ? string[1] - 'A' + 10 : string[1] - '0');
|
||||
if (checksum == parity) {
|
||||
gpsData.packetCount++;
|
||||
switch (gps_frame) {
|
||||
case FRAME_GGA:
|
||||
frameOK = 1;
|
||||
if (gps_Msg.fix) {
|
||||
gpsData.fix = 1;
|
||||
gpsData.latitude = gps_Msg.latitude;
|
||||
gpsData.longitude = gps_Msg.longitude;
|
||||
gpsData.numSat = gps_Msg.numSat;
|
||||
gpsData.altitude = gps_Msg.altitude;
|
||||
}
|
||||
break;
|
||||
case FRAME_RMC:
|
||||
gpsData.speed = gps_Msg.speed;
|
||||
gpsData.groundCourse = gps_Msg.groundCourse;
|
||||
break;
|
||||
} // end switch
|
||||
}
|
||||
else {
|
||||
gpsData.errorCount++;
|
||||
}
|
||||
}
|
||||
checksum_param = 0;
|
||||
break;
|
||||
default:
|
||||
if (offset < 15)
|
||||
string[offset++] = c;
|
||||
if (!checksum_param)
|
||||
parity ^= c;
|
||||
}
|
||||
return frameOK;
|
||||
}
|
||||
|
||||
bool gpsNewFrame(uint8_t c)
|
||||
{
|
||||
return gpsNewFrameNMEA(c);
|
||||
}
|
||||
|
||||
void gpsNewData(uint8_t c)
|
||||
{
|
||||
if (!gpsNewFrame(c)) {
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
void gpsWakeup()
|
||||
{
|
||||
uint8_t byte;
|
||||
while (gpsGetByte(&byte)) {
|
||||
gpsNewData(byte);
|
||||
}
|
||||
}
|
43
radio/src/gps.h
Normal file
43
radio/src/gps.h
Normal file
|
@ -0,0 +1,43 @@
|
|||
/*
|
||||
* Copyright (C) OpenTX
|
||||
*
|
||||
* Based on code named
|
||||
* cleanflight - https://github.com/cleanflight
|
||||
* th9x - http://code.google.com/p/th9x
|
||||
* er9x - http://code.google.com/p/er9x
|
||||
* gruvin9x - http://code.google.com/p/gruvin9x
|
||||
*
|
||||
* License GPLv2: http://www.gnu.org/licenses/gpl-2.0.html
|
||||
*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License version 2 as
|
||||
* published by the Free Software Foundation.
|
||||
*
|
||||
* 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.
|
||||
*/
|
||||
|
||||
#ifndef _GPS_H_
|
||||
#define _GPS_H_
|
||||
|
||||
#include <inttypes.h>
|
||||
|
||||
struct gpsdata_t
|
||||
{
|
||||
int32_t longitude; // degrees * 1.000.000
|
||||
int32_t latitude; // degrees * 1.000.000
|
||||
uint8_t fix;
|
||||
uint8_t numSat;
|
||||
uint32_t packetCount;
|
||||
uint32_t errorCount;
|
||||
uint16_t altitude; // altitude in 0.1m
|
||||
uint16_t speed; // speed in 0.1m/s
|
||||
uint16_t groundCourse; // degrees * 10
|
||||
};
|
||||
|
||||
extern gpsdata_t gpsData;
|
||||
void gpsWakeup();
|
||||
|
||||
#endif // _GPS_H_
|
|
@ -761,7 +761,7 @@ void drawTimer(coord_t x, coord_t y, putstime_t tme, LcdFlags att, LcdFlags att2
|
|||
lcdDrawNumber(lcdNextPos, y, qr.rem, (att2|LEADING0|LEFT) & (~RIGHT), 2);
|
||||
}
|
||||
|
||||
// TODO to be optimized with putsValueWithUnit
|
||||
// TODO to be optimized with drawValueWithUnit
|
||||
void putsVolts(coord_t x, coord_t y, uint16_t volts, LcdFlags att)
|
||||
{
|
||||
lcdDrawNumber(x, y, (int16_t)volts, (~NO_UNIT) & (att | ((att&PREC2)==PREC2 ? 0 : PREC1)));
|
||||
|
@ -1027,7 +1027,7 @@ const pm_uint8_t bchunit_ar[] PROGMEM = {
|
|||
UNIT_DIST, // GPS Alt
|
||||
};
|
||||
|
||||
void putsValueWithUnit(coord_t x, coord_t y, lcdint_t val, uint8_t unit, LcdFlags att)
|
||||
void drawValueWithUnit(coord_t x, coord_t y, lcdint_t val, uint8_t unit, LcdFlags att)
|
||||
{
|
||||
// convertUnit(val, unit);
|
||||
lcdDrawNumber(x, y, val, att & (~NO_UNIT));
|
||||
|
@ -1036,7 +1036,7 @@ void putsValueWithUnit(coord_t x, coord_t y, lcdint_t val, uint8_t unit, LcdFlag
|
|||
}
|
||||
}
|
||||
|
||||
void displayGpsCoord(coord_t x, coord_t y, int32_t value, const char * direction, LcdFlags att, bool seconds=true)
|
||||
void drawGPSCoord(coord_t x, coord_t y, int32_t value, const char * direction, LcdFlags att, bool seconds=true)
|
||||
{
|
||||
uint32_t absvalue = abs(value);
|
||||
lcdDrawNumber(x, y, absvalue / 1000000, att); // ddd
|
||||
|
@ -1064,7 +1064,7 @@ void displayGpsCoord(coord_t x, coord_t y, int32_t value, const char * direction
|
|||
lcdDrawSizedText(lcdLastPos+1, y, direction + (value>=0 ? 0 : 1), 1);
|
||||
}
|
||||
|
||||
void displayDate(coord_t x, coord_t y, TelemetryItem & telemetryItem, LcdFlags att)
|
||||
void drawDate(coord_t x, coord_t y, TelemetryItem & telemetryItem, LcdFlags att)
|
||||
{
|
||||
if (att & DBLSIZE) {
|
||||
x -= 42;
|
||||
|
@ -1090,69 +1090,26 @@ void displayDate(coord_t x, coord_t y, TelemetryItem & telemetryItem, LcdFlags a
|
|||
}
|
||||
}
|
||||
|
||||
void displayGpsCoords(coord_t x, coord_t y, TelemetryItem & telemetryItem, LcdFlags att)
|
||||
void drawGPSPosition(coord_t x, coord_t y, int32_t longitude, int32_t latitude, LcdFlags flags)
|
||||
{
|
||||
if (att & DBLSIZE) {
|
||||
if (flags & DBLSIZE) {
|
||||
x -= (g_eeGeneral.gpsFormat == 0 ? 54 : 51);
|
||||
att &= ~0x0F00; // TODO constant
|
||||
displayGpsCoord(x, y, telemetryItem.gps.longitude, "EW", att);
|
||||
displayGpsCoord(x, y+FH, telemetryItem.gps.latitude, "NS", att);
|
||||
flags &= ~0x0F00; // TODO constant
|
||||
drawGPSCoord(x, y, longitude, "EW", flags);
|
||||
drawGPSCoord(x, y+FH, latitude, "NS", flags);
|
||||
}
|
||||
else {
|
||||
displayGpsCoord(x, y, telemetryItem.gps.longitude, "EW", att, false);
|
||||
displayGpsCoord(lcdNextPos+FWNUM, y, telemetryItem.gps.latitude, "NS", att, false);
|
||||
drawGPSCoord(x, y, longitude, "EW", flags, false);
|
||||
drawGPSCoord(lcdNextPos+FWNUM, y, latitude, "NS", flags, false);
|
||||
}
|
||||
}
|
||||
|
||||
void putsTelemetryChannelValue(coord_t x, coord_t y, uint8_t channel, lcdint_t value, LcdFlags att)
|
||||
void drawGPSSensorValue(coord_t x, coord_t y, TelemetryItem & telemetryItem, LcdFlags flags)
|
||||
{
|
||||
if (channel >= MAX_TELEMETRY_SENSORS) return;
|
||||
TelemetryItem & telemetryItem = telemetryItems[channel];
|
||||
TelemetrySensor & telemetrySensor = g_model.telemetrySensors[channel];
|
||||
if (telemetrySensor.unit == UNIT_DATETIME) {
|
||||
displayDate(x, y, telemetryItem, att);
|
||||
}
|
||||
else if (telemetrySensor.unit == UNIT_GPS) {
|
||||
displayGpsCoords(x, y, telemetryItem, att);
|
||||
}
|
||||
else {
|
||||
LcdFlags flags = att;
|
||||
if (telemetrySensor.prec==2)
|
||||
flags |= PREC2;
|
||||
else if (telemetrySensor.prec==1)
|
||||
flags |= PREC1;
|
||||
putsValueWithUnit(x, y, value, telemetrySensor.unit == UNIT_CELLS ? UNIT_VOLTS : telemetrySensor.unit, flags);
|
||||
}
|
||||
drawGPSPosition(x, y, telemetryItem.gps.longitude, telemetryItem.gps.latitude, flags);
|
||||
}
|
||||
|
||||
void putsChannelValue(coord_t x, coord_t y, source_t channel, lcdint_t value, LcdFlags att)
|
||||
{
|
||||
if (channel >= MIXSRC_FIRST_TELEM) {
|
||||
channel = (channel-MIXSRC_FIRST_TELEM) / 3;
|
||||
putsTelemetryChannelValue(x, y, channel, value, att);
|
||||
}
|
||||
else if (channel >= MIXSRC_FIRST_TIMER || channel == MIXSRC_TX_TIME) {
|
||||
drawTimer(x, y, value, att, att);
|
||||
}
|
||||
else if (channel == MIXSRC_TX_VOLTAGE) {
|
||||
lcdDrawNumber(x, y, value, att|PREC1);
|
||||
}
|
||||
else {
|
||||
if (channel <= MIXSRC_LAST_CH) {
|
||||
value = calcRESXto100(value);
|
||||
}
|
||||
lcdDrawNumber(x, y, value, att);
|
||||
}
|
||||
}
|
||||
|
||||
void putsChannel(coord_t x, coord_t y, source_t channel, LcdFlags att)
|
||||
{
|
||||
getvalue_t value = getValue(channel);
|
||||
putsChannelValue(x, y, channel, value, att);
|
||||
}
|
||||
|
||||
#elif defined(TELEMETRY_FRSKY)
|
||||
void putsValueWithUnit(coord_t x, coord_t y, lcdint_t val, uint8_t unit, LcdFlags att)
|
||||
void drawValueWithUnit(coord_t x, coord_t y, lcdint_t val, uint8_t unit, LcdFlags att)
|
||||
{
|
||||
convertUnit(val, unit);
|
||||
lcdDrawNumber(x, y, val, att & (~NO_UNIT));
|
||||
|
@ -1172,37 +1129,21 @@ const pm_uint8_t bchunit_ar[] PROGMEM = {
|
|||
UNIT_DIST, // GPS Alt
|
||||
};
|
||||
|
||||
void putsTelemetryChannelValue(coord_t x, coord_t y, uint8_t channel, lcdint_t val, LcdFlags att)
|
||||
void drawTelemetryValue(coord_t x, coord_t y, uint8_t channel, lcdint_t val, LcdFlags att)
|
||||
{
|
||||
switch (channel) {
|
||||
#if defined(CPUARM) && defined(RTCLOCK)
|
||||
case TELEM_TX_TIME-1:
|
||||
drawRtcTime(x, y, att);
|
||||
break;
|
||||
#endif
|
||||
case TELEM_TIMER1-1:
|
||||
case TELEM_TIMER2-1:
|
||||
#if defined(CPUARM)
|
||||
case TELEM_TIMER3-1:
|
||||
#endif
|
||||
att &= ~NO_UNIT;
|
||||
drawTimer(x, y, val, att, att);
|
||||
break;
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
|
||||
case TELEM_MIN_A1-1:
|
||||
case TELEM_MIN_A2-1:
|
||||
#if defined(CPUARM)
|
||||
case TELEM_MIN_A3-1:
|
||||
case TELEM_MIN_A4-1:
|
||||
#endif
|
||||
channel -= TELEM_MIN_A1-TELEM_A1;
|
||||
// no break
|
||||
case TELEM_A1-1:
|
||||
case TELEM_A2-1:
|
||||
#if defined(CPUARM)
|
||||
case TELEM_A3-1:
|
||||
case TELEM_A4-1:
|
||||
#endif
|
||||
channel -= TELEM_A1-1;
|
||||
// A1 and A2
|
||||
{
|
||||
|
@ -1219,14 +1160,13 @@ void putsTelemetryChannelValue(coord_t x, coord_t y, uint8_t channel, lcdint_t v
|
|||
att |= PREC1;
|
||||
}
|
||||
}
|
||||
putsValueWithUnit(x, y, converted_value, g_model.frsky.channels[channel].type, att);
|
||||
drawValueWithUnit(x, y, converted_value, g_model.frsky.channels[channel].type, att);
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
|
||||
case TELEM_CELL-1:
|
||||
case TELEM_MIN_CELL-1:
|
||||
putsValueWithUnit(x, y, val, UNIT_VOLTS, att|PREC2);
|
||||
drawValueWithUnit(x, y, val, UNIT_VOLTS, att|PREC2);
|
||||
break;
|
||||
|
||||
case TELEM_TX_VOLTAGE-1:
|
||||
|
@ -1234,60 +1174,57 @@ void putsTelemetryChannelValue(coord_t x, coord_t y, uint8_t channel, lcdint_t v
|
|||
case TELEM_CELLS_SUM-1:
|
||||
case TELEM_MIN_CELLS_SUM-1:
|
||||
case TELEM_MIN_VFAS-1:
|
||||
putsValueWithUnit(x, y, val, UNIT_VOLTS, att|PREC1);
|
||||
drawValueWithUnit(x, y, val, UNIT_VOLTS, att|PREC1);
|
||||
break;
|
||||
|
||||
case TELEM_CURRENT-1:
|
||||
case TELEM_MAX_CURRENT-1:
|
||||
putsValueWithUnit(x, y, val, UNIT_AMPS, att|PREC1);
|
||||
drawValueWithUnit(x, y, val, UNIT_AMPS, att|PREC1);
|
||||
break;
|
||||
|
||||
case TELEM_CONSUMPTION-1:
|
||||
putsValueWithUnit(x, y, val, UNIT_MAH, att);
|
||||
drawValueWithUnit(x, y, val, UNIT_MAH, att);
|
||||
break;
|
||||
|
||||
case TELEM_POWER-1:
|
||||
case TELEM_MAX_POWER-1:
|
||||
putsValueWithUnit(x, y, val, UNIT_WATTS, att);
|
||||
drawValueWithUnit(x, y, val, UNIT_WATTS, att);
|
||||
break;
|
||||
|
||||
case TELEM_ACCx-1:
|
||||
case TELEM_ACCy-1:
|
||||
case TELEM_ACCz-1:
|
||||
putsValueWithUnit(x, y, val, UNIT_RAW, att|PREC2);
|
||||
drawValueWithUnit(x, y, val, UNIT_RAW, att|PREC2);
|
||||
break;
|
||||
|
||||
case TELEM_VSPEED-1:
|
||||
putsValueWithUnit(x, y, div_and_round(val, 10), UNIT_RAW, att|PREC1);
|
||||
drawValueWithUnit(x, y, div_and_round(val, 10), UNIT_RAW, att|PREC1);
|
||||
break;
|
||||
|
||||
case TELEM_ASPEED-1:
|
||||
case TELEM_MAX_ASPEED-1:
|
||||
putsValueWithUnit(x, y, val, UNIT_KTS, att|PREC1);
|
||||
drawValueWithUnit(x, y, val, UNIT_KTS, att|PREC1);
|
||||
break;
|
||||
|
||||
#if defined(CPUARM)
|
||||
case TELEM_SWR-1:
|
||||
#endif
|
||||
case TELEM_RSSI_TX-1:
|
||||
case TELEM_RSSI_RX-1:
|
||||
putsValueWithUnit(x, y, val, UNIT_RAW, att);
|
||||
drawValueWithUnit(x, y, val, UNIT_RAW, att);
|
||||
break;
|
||||
|
||||
case TELEM_HDG-1:
|
||||
putsValueWithUnit(x, y, val, UNIT_HDG, att);
|
||||
drawValueWithUnit(x, y, val, UNIT_HDG, att);
|
||||
break;
|
||||
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
case TELEM_ALT-1:
|
||||
putsValueWithUnit(x, y, div_and_round(val, 10), UNIT_DIST, att|PREC1);
|
||||
drawValueWithUnit(x, y, div_and_round(val, 10), UNIT_DIST, att|PREC1);
|
||||
break;
|
||||
#elif defined(WS_HOW_HIGH)
|
||||
case TELEM_ALT-1:
|
||||
case TELEM_MIN_ALT-1:
|
||||
case TELEM_MAX_ALT-1:
|
||||
if (IS_IMPERIAL_ENABLE() && IS_USR_PROTO_WS_HOW_HIGH()) {
|
||||
putsValueWithUnit(x, y, val, UNIT_FEET, att);
|
||||
drawValueWithUnit(x, y, val, UNIT_FEET, att);
|
||||
break;
|
||||
}
|
||||
// no break
|
||||
|
@ -1302,13 +1239,13 @@ void putsTelemetryChannelValue(coord_t x, coord_t y, uint8_t channel, lcdint_t v
|
|||
unit = channel + 1 - TELEM_ALT;
|
||||
if (channel >= TELEM_MIN_ALT-1 && channel <= TELEM_MAX_ALT-1)
|
||||
unit = 0;
|
||||
putsValueWithUnit(x, y, val, pgm_read_byte(bchunit_ar+unit), att);
|
||||
drawValueWithUnit(x, y, val, pgm_read_byte(bchunit_ar+unit), att);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
#else // defined(TELEMETRY_FRSKY)
|
||||
void putsTelemetryChannelValue(coord_t x, coord_t y, uint8_t channel, lcdint_t val, uint8_t att)
|
||||
void drawTelemetryValue(coord_t x, coord_t y, uint8_t channel, lcdint_t val, uint8_t att)
|
||||
{
|
||||
switch (channel) {
|
||||
case TELEM_TIMER1-1:
|
||||
|
|
|
@ -201,9 +201,14 @@ void putsVolts(coord_t x, coord_t y, uint16_t volts, LcdFlags att);
|
|||
void putsVBat(coord_t x, coord_t y, LcdFlags att);
|
||||
|
||||
#if !defined(BOOT)
|
||||
void putsChannelValue(coord_t x, coord_t y, source_t channel, lcdint_t val, LcdFlags att=0);
|
||||
void putsChannel(coord_t x, coord_t y, source_t channel, LcdFlags att=0);
|
||||
void putsTelemetryChannelValue(coord_t x, coord_t y, uint8_t channel, lcdint_t val, LcdFlags att=0);
|
||||
void drawSourceCustomValue(coord_t x, coord_t y, source_t channel, lcdint_t val, LcdFlags att=0);
|
||||
void drawSourceValue(coord_t x, coord_t y, source_t channel, LcdFlags att=0);
|
||||
#endif
|
||||
|
||||
#if defined(CPUARM)
|
||||
void drawSensorCustomValue(coord_t x, coord_t y, uint8_t channel, lcdint_t value, LcdFlags att);
|
||||
#else
|
||||
void drawTelemetryValue(coord_t x, coord_t y, uint8_t channel, lcdint_t val, LcdFlags att=0);
|
||||
#endif
|
||||
|
||||
#if defined(CPUARM)
|
||||
|
@ -216,6 +221,10 @@ void putsTelemetryChannelValue(coord_t x, coord_t y, uint8_t channel, lcdint_t v
|
|||
|
||||
void drawRtcTime(coord_t x, coord_t y, LcdFlags att);
|
||||
void drawTimer(coord_t x, coord_t y, putstime_t tme, LcdFlags att, LcdFlags att2);
|
||||
inline void drawTimer(coord_t x, coord_t y, putstime_t tme, LcdFlags att)
|
||||
{
|
||||
drawTimer(x, y, tme, att, att);
|
||||
}
|
||||
|
||||
#define SOLID 0xff
|
||||
#define DOTTED 0x55
|
||||
|
|
|
@ -185,12 +185,12 @@ void menuModelDisplay(uint8_t event)
|
|||
int barMin = -barMax;
|
||||
if (barSource) {
|
||||
if (barSource <= MIXSRC_LAST_CH) {
|
||||
putsChannelValue(DISPLAY_COL2, y, barSource, calc100toRESX(bar.barMin), (menuHorizontalPosition==1 ? attr : 0) | LEFT);
|
||||
putsChannelValue(DISPLAY_COL3, y, barSource, calc100toRESX(bar.barMax), (menuHorizontalPosition==2 ? attr : 0) | LEFT);
|
||||
drawSourceCustomValue(DISPLAY_COL2, y, barSource, calc100toRESX(bar.barMin), (menuHorizontalPosition==1 ? attr : 0) | LEFT);
|
||||
drawSourceCustomValue(DISPLAY_COL3, y, barSource, calc100toRESX(bar.barMax), (menuHorizontalPosition==2 ? attr : 0) | LEFT);
|
||||
}
|
||||
else {
|
||||
putsChannelValue(DISPLAY_COL2, y, barSource, bar.barMin, (menuHorizontalPosition==1 ? attr : 0) | LEFT);
|
||||
putsChannelValue(DISPLAY_COL3, y, barSource, bar.barMax, (menuHorizontalPosition==2 ? attr : 0) | LEFT);
|
||||
drawSourceCustomValue(DISPLAY_COL2, y, barSource, bar.barMin, (menuHorizontalPosition==1 ? attr : 0) | LEFT);
|
||||
drawSourceCustomValue(DISPLAY_COL3, y, barSource, bar.barMax, (menuHorizontalPosition==2 ? attr : 0) | LEFT);
|
||||
}
|
||||
}
|
||||
else if (attr) {
|
||||
|
|
|
@ -217,7 +217,7 @@ void menuModelExpoOne(uint8_t event)
|
|||
|
||||
case EXPO_FIELD_SCALE:
|
||||
lcdDrawTextAlignedLeft(y, STR_SCALE);
|
||||
putsTelemetryChannelValue(EXPO_ONE_2ND_COLUMN, y, (ed->srcRaw - MIXSRC_FIRST_TELEM)/3, convertTelemValue(ed->srcRaw - MIXSRC_FIRST_TELEM + 1, ed->scale), attr);
|
||||
drawSensorCustomValue(EXPO_ONE_2ND_COLUMN, y, (ed->srcRaw - MIXSRC_FIRST_TELEM)/3, convertTelemValue(ed->srcRaw - MIXSRC_FIRST_TELEM + 1, ed->scale), attr);
|
||||
if (attr) ed->scale = checkIncDec(event, ed->scale, 0, maxTelemValue(ed->srcRaw - MIXSRC_FIRST_TELEM + 1), EE_MODEL);
|
||||
break;
|
||||
|
||||
|
@ -274,7 +274,7 @@ void menuModelExpoOne(uint8_t event)
|
|||
|
||||
int x512 = getValue(ed->srcRaw);
|
||||
if (ed->srcRaw >= MIXSRC_FIRST_TELEM) {
|
||||
putsTelemetryChannelValue(LCD_W-8, 6*FH, (ed->srcRaw - MIXSRC_FIRST_TELEM) / 3, x512, 0);
|
||||
drawSensorCustomValue(LCD_W-8, 6*FH, (ed->srcRaw - MIXSRC_FIRST_TELEM) / 3, x512, 0);
|
||||
if (ed->scale > 0) x512 = (x512 * 1024) / convertTelemValue(ed->srcRaw - MIXSRC_FIRST_TELEM + 1, ed->scale);
|
||||
}
|
||||
else {
|
||||
|
|
|
@ -157,9 +157,9 @@ void menuModelLogicalSwitchOne(uint8_t event)
|
|||
#if defined(TELEMETRY_FRSKY)
|
||||
if (v1_val >= MIXSRC_FIRST_TELEM) {
|
||||
#if defined(CPUARM)
|
||||
putsChannelValue(CSWONE_2ND_COLUMN, y, v1_val, convertLswTelemValue(cs), attr|LEFT);
|
||||
drawSourceCustomValue(CSWONE_2ND_COLUMN, y, v1_val, convertLswTelemValue(cs), attr|LEFT);
|
||||
#else
|
||||
putsTelemetryChannelValue(CSWONE_2ND_COLUMN, y, v1_val - MIXSRC_FIRST_TELEM, convertLswTelemValue(cs), attr|LEFT);
|
||||
drawTelemetryValue(CSWONE_2ND_COLUMN, y, v1_val - MIXSRC_FIRST_TELEM, convertLswTelemValue(cs), attr|LEFT);
|
||||
#endif
|
||||
v2_max = maxTelemValue(v1_val - MIXSRC_FIRST_TELEM + 1);
|
||||
if (cs->func == LS_FUNC_DIFFEGREATER)
|
||||
|
@ -276,9 +276,9 @@ void menuModelLogicalSwitches(uint8_t event)
|
|||
drawSource(CSW_2ND_COLUMN, y, v1, 0);
|
||||
if (v1 >= MIXSRC_FIRST_TELEM) {
|
||||
#if defined(CPUARM)
|
||||
putsChannelValue(CSW_3RD_COLUMN, y, v1, convertLswTelemValue(cs), LEFT);
|
||||
drawSourceCustomValue(CSW_3RD_COLUMN, y, v1, convertLswTelemValue(cs), LEFT);
|
||||
#else
|
||||
putsTelemetryChannelValue(CSW_3RD_COLUMN, y, v1 - MIXSRC_FIRST_TELEM, convertLswTelemValue(cs), LEFT);
|
||||
drawTelemetryValue(CSW_3RD_COLUMN, y, v1 - MIXSRC_FIRST_TELEM, convertLswTelemValue(cs), LEFT);
|
||||
#endif
|
||||
}
|
||||
else {
|
||||
|
@ -385,27 +385,13 @@ void menuModelLogicalSwitches(uint8_t event)
|
|||
INCDEC_ENABLE_CHECK(NULL);
|
||||
}
|
||||
#if defined(CPUARM)
|
||||
putsChannelValue(CSW_3RD_COLUMN, y, v1_val, calc100toRESX(cs->v2), LEFT|attr2);
|
||||
drawSourceCustomValue(CSW_3RD_COLUMN, y, v1_val, calc100toRESX(cs->v2), LEFT|attr2);
|
||||
v2_min = -30000;
|
||||
v2_max = 30000;
|
||||
#elif defined(TELEMETRY_FRSKY)
|
||||
if (v1_val >= MIXSRC_FIRST_TELEM) {
|
||||
putsTelemetryChannelValue(CSW_3RD_COLUMN, y, v1_val - MIXSRC_FIRST_TELEM, convertLswTelemValue(cs), LEFT|attr2);
|
||||
drawTelemetryValue(CSW_3RD_COLUMN, y, v1_val - MIXSRC_FIRST_TELEM, convertLswTelemValue(cs), LEFT|attr2);
|
||||
v2_max = maxTelemValue(v1_val - MIXSRC_FIRST_TELEM + 1);
|
||||
#if defined(CPUARM)
|
||||
if (cs->func == LS_FUNC_DIFFEGREATER)
|
||||
v2_min = -v2_max;
|
||||
else if (cs->func == LS_FUNC_ADIFFEGREATER)
|
||||
v2_min = 0;
|
||||
else
|
||||
v2_min = minTelemValue(v1_val - MIXSRC_FIRST_TELEM + 1);
|
||||
if (horz == 2 && v2_max-v2_min > 1000)
|
||||
INCDEC_SET_FLAG(EE_MODEL | INCDEC_REP10 | NO_INCDEC_MARKS);
|
||||
if (cs->v2 < v2_min || cs->v2 > v2_max) {
|
||||
cs->v2 = 0;
|
||||
storageDirty(EE_MODEL);
|
||||
}
|
||||
#else
|
||||
if (cstate == LS_FAMILY_OFS) {
|
||||
v2_min = -128;
|
||||
v2_max -= 128;
|
||||
|
@ -418,11 +404,10 @@ void menuModelLogicalSwitches(uint8_t event)
|
|||
cs->v2 = v2_max;
|
||||
storageDirty(EE_MODEL);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
else {
|
||||
lcdDrawNumber(CSW_3RD_COLUMN, y, cs->v2, LEFT|attr2);
|
||||
#if defined(CPUARM) && defined(GVARS)
|
||||
#if defined(GVARS)
|
||||
if (v1_val >= MIXSRC_GVAR1) {
|
||||
v2_min = -1024; v2_max = +1024;
|
||||
}
|
||||
|
@ -434,7 +419,7 @@ void menuModelLogicalSwitches(uint8_t event)
|
|||
}
|
||||
#else
|
||||
if (v1_val >= MIXSRC_FIRST_TELEM) {
|
||||
putsTelemetryChannelValue(CSW_3RD_COLUMN, y, v1_val - MIXSRC_FIRST_TELEM, convertLswTelemValue(cs), LEFT|attr2);
|
||||
drawTelemetryValue(CSW_3RD_COLUMN, y, v1_val - MIXSRC_FIRST_TELEM, convertLswTelemValue(cs), LEFT|attr2);
|
||||
v2_min = -128; v2_max = 127;
|
||||
}
|
||||
else {
|
||||
|
|
|
@ -219,7 +219,7 @@ void menuModelSensor(uint8_t event)
|
|||
SUBMENU(STR_MENUSENSOR, SENSOR_FIELD_MAX, {0, 0, sensor->type == TELEM_TYPE_CALCULATED ? (uint8_t)0 : (uint8_t)1, SENSOR_UNIT_ROWS, SENSOR_PREC_ROWS, SENSOR_PARAM1_ROWS, SENSOR_PARAM2_ROWS, SENSOR_PARAM3_ROWS, SENSOR_PARAM4_ROWS, SENSOR_AUTOOFFSET_ROWS, SENSOR_FILTER_ROWS, SENSOR_PERSISTENT_ROWS, 0 });
|
||||
lcdDrawNumber(PSIZE(TR_MENUSENSOR)*FW+1, 0, s_currIdx+1, INVERS|LEFT);
|
||||
|
||||
putsTelemetryChannelValue(SENSOR_2ND_COLUMN, 0, s_currIdx, getValue(MIXSRC_FIRST_TELEM+3*s_currIdx), LEFT);
|
||||
drawSensorCustomValue(SENSOR_2ND_COLUMN, 0, s_currIdx, getValue(MIXSRC_FIRST_TELEM+3*s_currIdx), LEFT);
|
||||
|
||||
int8_t sub = menuVerticalPosition;
|
||||
|
||||
|
@ -518,7 +518,7 @@ void menuModelTelemetryFrsky(uint8_t event)
|
|||
bool isOld = telemetryItem.isOld();
|
||||
lcdNextPos = TELEM_COL2;
|
||||
if (isOld) lcdDrawChar(lcdNextPos, y, '[');
|
||||
putsTelemetryChannelValue(lcdNextPos, y, index, getValue(MIXSRC_FIRST_TELEM+3*index), LEFT);
|
||||
drawSensorCustomValue(lcdNextPos, y, index, getValue(MIXSRC_FIRST_TELEM+3*index), LEFT);
|
||||
if (isOld) lcdDrawChar(lcdLastPos, y, ']');
|
||||
}
|
||||
else {
|
||||
|
@ -603,13 +603,13 @@ void menuModelTelemetryFrsky(uint8_t event)
|
|||
case ITEM_TELEMETRY_A2_LABEL:
|
||||
lcdDrawTextAlignedLeft(y, STR_ACHANNEL);
|
||||
lcdDrawNumber(2*FW, y, ch+1, 0);
|
||||
putsTelemetryChannelValue(TELEM_COL2+6*FW, y, dest, telemetryData.analog[ch].value, LEFT);
|
||||
drawTelemetryValue(TELEM_COL2+6*FW, y, dest, telemetryData.analog[ch].value, LEFT);
|
||||
break;
|
||||
|
||||
case ITEM_TELEMETRY_A1_RANGE:
|
||||
case ITEM_TELEMETRY_A2_RANGE:
|
||||
lcdDrawTextAlignedLeft(y, STR_RANGE);
|
||||
putsTelemetryChannelValue(TELEM_COL2, y, dest, 255-channel.offset, (menuHorizontalPosition<=0 ? attr : 0)|NO_UNIT|LEFT);
|
||||
drawTelemetryValue(TELEM_COL2, y, dest, 255-channel.offset, (menuHorizontalPosition<=0 ? attr : 0)|NO_UNIT|LEFT);
|
||||
lcdDrawTextAtIndex(lcdLastPos, y, STR_VTELEMUNIT, channel.type, menuHorizontalPosition!=0 ? attr : 0);
|
||||
if (attr && (s_editMode>0 || p1valdiff)) {
|
||||
if (menuHorizontalPosition == 0) {
|
||||
|
@ -635,7 +635,7 @@ void menuModelTelemetryFrsky(uint8_t event)
|
|||
case ITEM_TELEMETRY_A1_OFFSET:
|
||||
case ITEM_TELEMETRY_A2_OFFSET:
|
||||
lcdDrawTextAlignedLeft(y, STR_OFFSET);
|
||||
putsTelemetryChannelValue(TELEM_COL2, y, dest, 0, LEFT|attr);
|
||||
drawTelemetryValue(TELEM_COL2, y, dest, 0, LEFT|attr);
|
||||
if (attr) channel.offset = checkIncDec(event, channel.offset, -256, 256, EE_MODEL);
|
||||
break;
|
||||
|
||||
|
@ -648,7 +648,7 @@ void menuModelTelemetryFrsky(uint8_t event)
|
|||
lcdDrawTextAlignedLeft(y, STR_ALARM);
|
||||
lcdDrawTextAtIndex(TELEM_COL2, y, STR_VALARM, ALARM_LEVEL(ch, alarm), menuHorizontalPosition<=0 ? attr : 0);
|
||||
lcdDrawTextAtIndex(TELEM_COL2+4*FW, y, STR_VALARMFN, ALARM_GREATER(ch, alarm), (CURSOR_ON_LINE() || menuHorizontalPosition==1) ? attr : 0);
|
||||
putsTelemetryChannelValue(TELEM_COL2+6*FW, y, dest, channel.alarms_value[alarm], ((CURSOR_ON_LINE() || menuHorizontalPosition==2) ? attr : 0) | LEFT);
|
||||
drawTelemetryValue(TELEM_COL2+6*FW, y, dest, channel.alarms_value[alarm], ((CURSOR_ON_LINE() || menuHorizontalPosition==2) ? attr : 0) | LEFT);
|
||||
|
||||
if (attr && (s_editMode>0 || p1valdiff)) {
|
||||
uint8_t t;
|
||||
|
@ -837,8 +837,8 @@ void menuModelTelemetryFrsky(uint8_t event)
|
|||
source_t barSource = bar.source;
|
||||
lcdDrawTextAtIndex(TELEM_COL1, y, STR_VTELEMCHNS, barSource, menuHorizontalPosition==0 ? attr : 0);
|
||||
if (barSource) {
|
||||
putsTelemetryChannelValue(TELEM_BARS_COLMIN, y, barSource-1, convertBarTelemValue(barSource, bar.barMin), (menuHorizontalPosition==1 ? attr : 0) | LEFT);
|
||||
putsTelemetryChannelValue(TELEM_BARS_COLMAX, y, barSource-1, convertBarTelemValue(barSource, 255-bar.barMax), (menuHorizontalPosition==2 ? attr : 0) | LEFT);
|
||||
drawTelemetryValue(TELEM_BARS_COLMIN, y, barSource-1, convertBarTelemValue(barSource, bar.barMin), (menuHorizontalPosition==1 ? attr : 0) | LEFT);
|
||||
drawTelemetryValue(TELEM_BARS_COLMAX, y, barSource-1, convertBarTelemValue(barSource, 255-bar.barMax), (menuHorizontalPosition==2 ? attr : 0) | LEFT);
|
||||
}
|
||||
else if (attr && menuHorizontalPosition>0) {
|
||||
menuHorizontalPosition = 0;
|
||||
|
|
|
@ -89,7 +89,7 @@ void menuRadioDiagAnalogs(uint8_t event)
|
|||
|
||||
#if defined(TX_CAPACITY_MEASUREMENT)
|
||||
lcdDrawTextAlignedLeft(6*FH+1, STR_CURRENT_CALIB);
|
||||
putsValueWithUnit(LEN_CALIB_FIELDS*FW+4*FW, 6*FH+1, getCurrent(), UNIT_MILLIAMPS, (menuVerticalPosition==2 ? INVERS : 0)) ;
|
||||
drawValueWithUnit(LEN_CALIB_FIELDS*FW+4*FW, 6*FH+1, getCurrent(), UNIT_MILLIAMPS, (menuVerticalPosition==2 ? INVERS : 0)) ;
|
||||
if (menuVerticalPosition==2) CHECK_INCDEC_GENVAR(event, g_eeGeneral.txCurrentCalibration, -49, 49);
|
||||
#endif
|
||||
|
||||
|
@ -103,7 +103,7 @@ void menuRadioDiagAnalogs(uint8_t event)
|
|||
#endif
|
||||
|
||||
lcdDrawTextAlignedLeft(TEMP_CALIB_POS, STR_TEMP_CALIB);
|
||||
putsValueWithUnit(LEN_CALIB_FIELDS*FW+4*FW, TEMP_CALIB_POS, getTemperature(), UNIT_TEMPERATURE, (menuVerticalPosition==TEMP_CALIB_MENU_POS ? INVERS : 0)) ;
|
||||
drawValueWithUnit(LEN_CALIB_FIELDS*FW+4*FW, TEMP_CALIB_POS, getTemperature(), UNIT_TEMPERATURE, (menuVerticalPosition==TEMP_CALIB_MENU_POS ? INVERS : 0)) ;
|
||||
if (menuVerticalPosition==TEMP_CALIB_MENU_POS) CHECK_INCDEC_GENVAR(event, g_eeGeneral.temperatureCalib, -100, 100);
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -389,7 +389,7 @@ void menuRadioSetup(uint8_t event)
|
|||
#if defined(TX_CAPACITY_MEASUREMENT)
|
||||
case ITEM_SETUP_CAPACITY_WARNING:
|
||||
lcdDrawTextAlignedLeft(y, STR_CAPAWARNING);
|
||||
putsValueWithUnit(RADIO_SETUP_2ND_COLUMN, y, g_eeGeneral.mAhWarn*50, UNIT_MAH, attr|LEFT) ;
|
||||
drawValueWithUnit(RADIO_SETUP_2ND_COLUMN, y, g_eeGeneral.mAhWarn*50, UNIT_MAH, attr|LEFT) ;
|
||||
if(attr) CHECK_INCDEC_GENVAR(event, g_eeGeneral.mAhWarn, 0, 100);
|
||||
break;
|
||||
#endif
|
||||
|
@ -397,7 +397,7 @@ void menuRadioSetup(uint8_t event)
|
|||
#if defined(PCBSKY9X)
|
||||
case ITEM_SETUP_TEMPERATURE_WARNING:
|
||||
lcdDrawTextAlignedLeft(y, STR_TEMPWARNING);
|
||||
putsValueWithUnit(RADIO_SETUP_2ND_COLUMN, y, g_eeGeneral.temperatureWarn, UNIT_TEMPERATURE, attr|LEFT) ;
|
||||
drawValueWithUnit(RADIO_SETUP_2ND_COLUMN, y, g_eeGeneral.temperatureWarn, UNIT_TEMPERATURE, attr|LEFT) ;
|
||||
if(attr) CHECK_INCDEC_GENVAR(event, g_eeGeneral.temperatureWarn, 0, 120); // 0 means no alarm
|
||||
break;
|
||||
#endif
|
||||
|
|
|
@ -206,10 +206,10 @@ void displayBattVoltage()
|
|||
void displayVoltageOrAlarm()
|
||||
{
|
||||
if (g_eeGeneral.temperatureWarn && getTemperature() >= g_eeGeneral.temperatureWarn) {
|
||||
putsValueWithUnit(6*FW-1, 2*FH, getTemperature(), UNIT_TEMPERATURE, BLINK|INVERS|DBLSIZE|RIGHT);
|
||||
drawValueWithUnit(6*FW-1, 2*FH, getTemperature(), UNIT_TEMPERATURE, BLINK|INVERS|DBLSIZE|RIGHT);
|
||||
}
|
||||
else if (g_eeGeneral.mAhWarn && (g_eeGeneral.mAhUsed + Current_used * (488 + g_eeGeneral.txCurrentCalibration)/8192/36) / 500 >= g_eeGeneral.mAhWarn) {
|
||||
putsValueWithUnit(7*FW-1, 2*FH, (g_eeGeneral.mAhUsed + Current_used*(488 + g_eeGeneral.txCurrentCalibration)/8192/36)/10, UNIT_MAH, BLINK|INVERS|DBLSIZE|RIGHT);
|
||||
drawValueWithUnit(7*FW-1, 2*FH, (g_eeGeneral.mAhUsed + Current_used*(488 + g_eeGeneral.txCurrentCalibration)/8192/36)/10, UNIT_MAH, BLINK|INVERS|DBLSIZE|RIGHT);
|
||||
}
|
||||
else {
|
||||
displayBattVoltage();
|
||||
|
|
|
@ -134,20 +134,20 @@ void menuStatisticsDebug(uint8_t event)
|
|||
#if defined(TX_CAPACITY_MEASUREMENT)
|
||||
// current
|
||||
lcdDrawTextAlignedLeft(MENU_DEBUG_Y_CURRENT, STR_CPU_CURRENT);
|
||||
putsValueWithUnit(MENU_DEBUG_COL1_OFS, MENU_DEBUG_Y_CURRENT, getCurrent(), UNIT_MILLIAMPS, LEFT);
|
||||
drawValueWithUnit(MENU_DEBUG_COL1_OFS, MENU_DEBUG_Y_CURRENT, getCurrent(), UNIT_MILLIAMPS, LEFT);
|
||||
uint32_t current_scale = 488 + g_eeGeneral.txCurrentCalibration;
|
||||
lcdDrawChar(MENU_DEBUG_COL2_OFS, MENU_DEBUG_Y_CURRENT, '>');
|
||||
putsValueWithUnit(MENU_DEBUG_COL2_OFS+FW+1, MENU_DEBUG_Y_CURRENT, Current_max*10*current_scale/8192, UNIT_RAW, LEFT);
|
||||
drawValueWithUnit(MENU_DEBUG_COL2_OFS+FW+1, MENU_DEBUG_Y_CURRENT, Current_max*10*current_scale/8192, UNIT_RAW, LEFT);
|
||||
// consumption
|
||||
lcdDrawTextAlignedLeft(MENU_DEBUG_Y_MAH, STR_CPU_MAH);
|
||||
putsValueWithUnit(MENU_DEBUG_COL1_OFS, MENU_DEBUG_Y_MAH, g_eeGeneral.mAhUsed + Current_used*current_scale/8192/36, UNIT_MAH, LEFT|PREC1);
|
||||
drawValueWithUnit(MENU_DEBUG_COL1_OFS, MENU_DEBUG_Y_MAH, g_eeGeneral.mAhUsed + Current_used*current_scale/8192/36, UNIT_MAH, LEFT|PREC1);
|
||||
#endif
|
||||
|
||||
#if defined(PCBSKY9X)
|
||||
lcdDrawTextAlignedLeft(MENU_DEBUG_Y_CPU_TEMP, STR_CPU_TEMP);
|
||||
putsValueWithUnit(MENU_DEBUG_COL1_OFS, MENU_DEBUG_Y_CPU_TEMP, getTemperature(), UNIT_TEMPERATURE, LEFT);
|
||||
drawValueWithUnit(MENU_DEBUG_COL1_OFS, MENU_DEBUG_Y_CPU_TEMP, getTemperature(), UNIT_TEMPERATURE, LEFT);
|
||||
lcdDrawChar(MENU_DEBUG_COL2_OFS, MENU_DEBUG_Y_CPU_TEMP, '>');
|
||||
putsValueWithUnit(MENU_DEBUG_COL2_OFS+FW+1, MENU_DEBUG_Y_CPU_TEMP, maxTemperature+g_eeGeneral.temperatureCalib, UNIT_TEMPERATURE, LEFT);
|
||||
drawValueWithUnit(MENU_DEBUG_COL2_OFS+FW+1, MENU_DEBUG_Y_CPU_TEMP, maxTemperature+g_eeGeneral.temperatureCalib, UNIT_TEMPERATURE, LEFT);
|
||||
#endif
|
||||
|
||||
#if defined(COPROCESSOR)
|
||||
|
@ -163,8 +163,8 @@ void menuStatisticsDebug(uint8_t event)
|
|||
lcdDrawText(MENU_DEBUG_COL1_OFS, MENU_DEBUG_Y_COPROC, PSTR("Upgr.TinyApp"),INVERS);
|
||||
}
|
||||
else {
|
||||
putsValueWithUnit(MENU_DEBUG_COL1_OFS, MENU_DEBUG_Y_COPROC, Coproc_temp, UNIT_TEMPERATURE, LEFT);
|
||||
putsValueWithUnit(MENU_DEBUG_COL2_OFS, MENU_DEBUG_Y_COPROC, Coproc_maxtemp, UNIT_TEMPERATURE, LEFT);
|
||||
drawValueWithUnit(MENU_DEBUG_COL1_OFS, MENU_DEBUG_Y_COPROC, Coproc_temp, UNIT_TEMPERATURE, LEFT);
|
||||
drawValueWithUnit(MENU_DEBUG_COL2_OFS, MENU_DEBUG_Y_COPROC, Coproc_maxtemp, UNIT_TEMPERATURE, LEFT);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -67,7 +67,7 @@ void displayGpsTime()
|
|||
lcdInvertLastLine();
|
||||
}
|
||||
|
||||
void displayGpsCoord(uint8_t y, char direction, int16_t bp, int16_t ap)
|
||||
void drawGPSCoord(uint8_t y, char direction, int16_t bp, int16_t ap)
|
||||
{
|
||||
if (telemetryData.hub.gpsFix >= 0) {
|
||||
if (!direction) direction = '-';
|
||||
|
@ -99,7 +99,7 @@ void displayGpsCoord(uint8_t y, char direction, int16_t bp, int16_t ap)
|
|||
}
|
||||
#elif !defined(CPUARM)
|
||||
#define displayGpsTime()
|
||||
#define displayGpsCoord(...)
|
||||
#define drawGPSCoord(...)
|
||||
#endif
|
||||
|
||||
#if !defined(CPUARM)
|
||||
|
@ -107,9 +107,9 @@ void displayVoltageScreenLine(uint8_t y, uint8_t index)
|
|||
{
|
||||
drawStringWithIndex(0, y, STR_A, index+1, 0);
|
||||
if (TELEMETRY_STREAMING()) {
|
||||
putsTelemetryChannelValue(3*FW+6*FW+4, y-FH, index+TELEM_A1-1, telemetryData.analog[index].value, DBLSIZE);
|
||||
lcdDrawChar(12*FW-1, y-FH, '<'); putsTelemetryChannelValue(17*FW, y-FH, index+TELEM_A1-1, telemetryData.analog[index].min, NO_UNIT);
|
||||
lcdDrawChar(12*FW, y, '>'); putsTelemetryChannelValue(17*FW, y, index+TELEM_A1-1, telemetryData.analog[index].max, NO_UNIT);
|
||||
drawTelemetryValue(3*FW+6*FW+4, y-FH, index+TELEM_A1-1, telemetryData.analog[index].value, DBLSIZE);
|
||||
lcdDrawChar(12*FW-1, y-FH, '<'); drawTelemetryValue(17*FW, y-FH, index+TELEM_A1-1, telemetryData.analog[index].min, NO_UNIT);
|
||||
lcdDrawChar(12*FW, y, '>'); drawTelemetryValue(17*FW, y, index+TELEM_A1-1, telemetryData.analog[index].max, NO_UNIT);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
@ -142,10 +142,10 @@ void displayVoltagesScreen()
|
|||
break;
|
||||
#if defined(FRSKY_HUB)
|
||||
case FRSKY_VOLTS_SOURCE_FAS:
|
||||
putsTelemetryChannelValue(3*FW+6*FW+4, FH, TELEM_VFAS-1, telemetryData.hub.vfas, DBLSIZE);
|
||||
drawTelemetryValue(3*FW+6*FW+4, FH, TELEM_VFAS-1, telemetryData.hub.vfas, DBLSIZE);
|
||||
break;
|
||||
case FRSKY_VOLTS_SOURCE_CELLS:
|
||||
putsTelemetryChannelValue(3*FW+6*FW+4, FH, TELEM_CELLS_SUM-1, telemetryData.hub.cellsSum, DBLSIZE);
|
||||
drawTelemetryValue(3*FW+6*FW+4, FH, TELEM_CELLS_SUM-1, telemetryData.hub.cellsSum, DBLSIZE);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
|
@ -159,13 +159,13 @@ void displayVoltagesScreen()
|
|||
break;
|
||||
#if defined(FRSKY_HUB)
|
||||
case FRSKY_CURRENT_SOURCE_FAS:
|
||||
putsTelemetryChannelValue(3*FW+6*FW+4, 3*FH, TELEM_CURRENT-1, telemetryData.hub.current, DBLSIZE);
|
||||
drawTelemetryValue(3*FW+6*FW+4, 3*FH, TELEM_CURRENT-1, telemetryData.hub.current, DBLSIZE);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
|
||||
putsTelemetryChannelValue(4, 5*FH, TELEM_POWER-1, telemetryData.hub.power, LEFT|DBLSIZE);
|
||||
putsTelemetryChannelValue(3*FW+4+4*FW+6*FW+FW, 5*FH, TELEM_CONSUMPTION-1, telemetryData.hub.currentConsumption, DBLSIZE);
|
||||
drawTelemetryValue(4, 5*FH, TELEM_POWER-1, telemetryData.hub.power, LEFT|DBLSIZE);
|
||||
drawTelemetryValue(3*FW+4+4*FW+6*FW+FW, 5*FH, TELEM_CONSUMPTION-1, telemetryData.hub.currentConsumption, DBLSIZE);
|
||||
}
|
||||
else {
|
||||
displayVoltageScreenLine(analog > 0 ? 5*FH : 4*FH, analog ? 2-analog : 0);
|
||||
|
@ -198,11 +198,11 @@ void displayAfterFlightScreen()
|
|||
if (IS_GPS_AVAILABLE()) {
|
||||
// Latitude
|
||||
lcdDrawTextAlignedLeft(line, STR_LATITUDE);
|
||||
displayGpsCoord(line, telemetryData.hub.gpsLatitudeNS, telemetryData.hub.gpsLatitude_bp, telemetryData.hub.gpsLatitude_ap);
|
||||
drawGPSCoord(line, telemetryData.hub.gpsLatitudeNS, telemetryData.hub.gpsLatitude_bp, telemetryData.hub.gpsLatitude_ap);
|
||||
// Longitude
|
||||
line+=1*FH+1;
|
||||
lcdDrawTextAlignedLeft(line, STR_LONGITUDE);
|
||||
displayGpsCoord(line, telemetryData.hub.gpsLongitudeEW, telemetryData.hub.gpsLongitude_bp, telemetryData.hub.gpsLongitude_ap);
|
||||
drawGPSCoord(line, telemetryData.hub.gpsLongitudeEW, telemetryData.hub.gpsLongitude_bp, telemetryData.hub.gpsLongitude_ap);
|
||||
displayGpsTime();
|
||||
line+=1*FH+1;
|
||||
}
|
||||
|
@ -347,7 +347,7 @@ bool displayNumbersTelemetryScreen(FrSkyScreenData & screen)
|
|||
}
|
||||
}
|
||||
|
||||
putsChannel(pos[j+1]-2, (i==3 ? 1+FH+2*FH*i:FH+2*FH*i), field, att);
|
||||
drawSourceValue(pos[j+1]-2, (i==3 ? 1+FH+2*FH*i:FH+2*FH*i), field, att);
|
||||
|
||||
}
|
||||
}
|
||||
|
@ -394,7 +394,7 @@ bool displayNumbersTelemetryScreen(FrSkyScreenData & screen)
|
|||
getvalue_t value = getValue(MIXSRC_FIRST_TELEM+field-1);
|
||||
uint8_t att = (i==3 ? NO_UNIT : DBLSIZE|NO_UNIT);
|
||||
coord_t pos[] = {0, 65, 130};
|
||||
putsTelemetryChannelValue(pos[j+1]-2, FH+2*FH*i, field-1, value, att);
|
||||
drawTelemetryValue(pos[j+1]-2, FH+2*FH*i, field-1, value, att);
|
||||
|
||||
if (field >= TELEM_TIMER1 && field <= TELEM_TIMER_MAX && i!=3) {
|
||||
// there is not enough space on LCD for displaying "Tmr1" or "Tmr2" and still see the - sign, we write "T1" or "T2" instead
|
||||
|
|
|
@ -645,7 +645,7 @@ void drawTimer(coord_t x, coord_t y, putstime_t tme, LcdFlags att, LcdFlags att2
|
|||
lcdDrawNumber(lcdNextPos, y, qr.rem, (att2|LEADING0) & (~RIGHT), 2);
|
||||
}
|
||||
|
||||
// TODO to be optimized with putsValueWithUnit
|
||||
// TODO to be optimized with drawValueWithUnit
|
||||
void putsVolts(coord_t x, coord_t y, uint16_t volts, LcdFlags att)
|
||||
{
|
||||
lcdDrawNumber(x, y, (int16_t)volts, (~NO_UNIT) & (att | ((att&PREC2)==PREC2 ? 0 : PREC1)));
|
||||
|
@ -814,7 +814,7 @@ const pm_uint8_t bchunit_ar[] PROGMEM = {
|
|||
UNIT_DIST, // GPS Alt
|
||||
};
|
||||
|
||||
void putsValueWithUnit(coord_t x, coord_t y, int32_t val, uint8_t unit, LcdFlags att)
|
||||
void drawValueWithUnit(coord_t x, coord_t y, int32_t val, uint8_t unit, LcdFlags att)
|
||||
{
|
||||
// convertUnit(val, unit);
|
||||
lcdDrawNumber(x, y, val, att & (~NO_UNIT));
|
||||
|
@ -823,7 +823,7 @@ void putsValueWithUnit(coord_t x, coord_t y, int32_t val, uint8_t unit, LcdFlags
|
|||
}
|
||||
}
|
||||
|
||||
void displayGpsCoord(coord_t x, coord_t y, int32_t value, const char * direction, LcdFlags att, bool seconds=true)
|
||||
void drawGPSCoord(coord_t x, coord_t y, int32_t value, const char * direction, LcdFlags att, bool seconds=true)
|
||||
{
|
||||
uint32_t absvalue = abs(value);
|
||||
lcdDrawNumber(x, y, absvalue / 1000000, att); // ddd
|
||||
|
@ -837,8 +837,8 @@ void displayGpsCoord(coord_t x, coord_t y, int32_t value, const char * direction
|
|||
if (seconds) {
|
||||
absvalue %= 1000000;
|
||||
absvalue *= 60;
|
||||
absvalue /= 10000;
|
||||
lcdDrawNumber(lcdLastPos+2, y, absvalue, att|LEFT|PREC2);
|
||||
absvalue /= 100000;
|
||||
lcdDrawNumber(lcdLastPos+2, y, absvalue, att|LEFT|PREC1);
|
||||
lcdDrawSolidVerticalLine(lcdLastPos, y, 2);
|
||||
lcdDrawSolidVerticalLine(lcdLastPos+2, y, 2);
|
||||
lcdLastPos += 3;
|
||||
|
@ -851,7 +851,7 @@ void displayGpsCoord(coord_t x, coord_t y, int32_t value, const char * direction
|
|||
lcdDrawSizedText(lcdLastPos+1, y, direction + (value>=0 ? 0 : 1), 1);
|
||||
}
|
||||
|
||||
void displayDate(coord_t x, coord_t y, TelemetryItem & telemetryItem, LcdFlags att)
|
||||
void drawDate(coord_t x, coord_t y, TelemetryItem & telemetryItem, LcdFlags att)
|
||||
{
|
||||
if (att & DBLSIZE) {
|
||||
x -= 42;
|
||||
|
@ -882,125 +882,20 @@ void displayDate(coord_t x, coord_t y, TelemetryItem & telemetryItem, LcdFlags a
|
|||
}
|
||||
}
|
||||
|
||||
void displayGpsCoords(coord_t x, coord_t y, TelemetryItem & telemetryItem, LcdFlags att)
|
||||
void drawGPSSensorValue(coord_t x, coord_t y, TelemetryItem & telemetryItem, LcdFlags att)
|
||||
{
|
||||
if (att & DBLSIZE) {
|
||||
x -= (g_eeGeneral.gpsFormat == 0 ? 54 : 51);
|
||||
att &= ~0x0F00; // TODO constant
|
||||
displayGpsCoord(x, y, telemetryItem.gps.longitude, "EW", att);
|
||||
displayGpsCoord(x, y+FH, telemetryItem.gps.latitude, "NS", att);
|
||||
drawGPSCoord(x, y, telemetryItem.gps.longitude, "EW", att);
|
||||
drawGPSCoord(x, y+FH, telemetryItem.gps.latitude, "NS", att);
|
||||
}
|
||||
else {
|
||||
displayGpsCoord(x, y, telemetryItem.gps.longitude, "EW", att, false);
|
||||
displayGpsCoord(lcdNextPos+FWNUM, y, telemetryItem.gps.latitude, "NS", att, false);
|
||||
drawGPSCoord(x, y, telemetryItem.gps.longitude, "EW", att, false);
|
||||
drawGPSCoord(lcdNextPos+FWNUM, y, telemetryItem.gps.latitude, "NS", att, false);
|
||||
}
|
||||
}
|
||||
|
||||
void putsTelemetryChannelValue(coord_t x, coord_t y, uint8_t channel, int32_t value, LcdFlags att)
|
||||
{
|
||||
if (channel >= MAX_TELEMETRY_SENSORS)
|
||||
return; // Lua luaLcdDrawChannel() can call us with a bad value
|
||||
|
||||
TelemetryItem & telemetryItem = telemetryItems[channel];
|
||||
TelemetrySensor & telemetrySensor = g_model.telemetrySensors[channel];
|
||||
if (telemetrySensor.unit == UNIT_DATETIME) {
|
||||
displayDate(x, y, telemetryItem, att);
|
||||
}
|
||||
else if (telemetrySensor.unit == UNIT_GPS) {
|
||||
displayGpsCoords(x, y, telemetryItem, att);
|
||||
}
|
||||
else if (telemetrySensor.unit == UNIT_BITFIELD) {
|
||||
if (IS_FRSKY_SPORT_PROTOCOL()) {
|
||||
if (telemetrySensor.id >= RBOX_STATE_FIRST_ID && telemetrySensor.id <= RBOX_STATE_LAST_ID) {
|
||||
if (telemetrySensor.subId == 0) {
|
||||
if (value == 0) {
|
||||
lcdDrawText(x, y, "OK", att);
|
||||
}
|
||||
else {
|
||||
for (uint8_t i=0; i<16; i++) {
|
||||
if (value & (1 << i)) {
|
||||
char s[] = "CH__ KO";
|
||||
strAppendUnsigned(&s[2], i+1, 2);
|
||||
lcdDrawText(x, att & DBLSIZE ? y+1 : y, s, att & ~DBLSIZE);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else {
|
||||
if (value == 0) {
|
||||
lcdDrawText(x, att & DBLSIZE ? y+1 : y, "Rx OK", att & ~DBLSIZE);
|
||||
}
|
||||
else {
|
||||
static const char * const RXS_STATUS[] = {
|
||||
"Rx1 Ovl",
|
||||
"Rx2 Ovl",
|
||||
"SBUS Ovl",
|
||||
"Rx1 FS",
|
||||
"Rx1 LF",
|
||||
"Rx2 FS",
|
||||
"Rx2 LF",
|
||||
"Rx1 Lost",
|
||||
"Rx2 Lost",
|
||||
"Rx1 NS",
|
||||
"Rx2 NS",
|
||||
};
|
||||
for (uint8_t i=0; i<DIM(RXS_STATUS); i++) {
|
||||
if (value & (1<<i)) {
|
||||
lcdDrawText(x, att & DBLSIZE ? y+1 : y, RXS_STATUS[i], att & ~DBLSIZE);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else if (telemetrySensor.unit == UNIT_TEXT) {
|
||||
lcdDrawSizedText(x, att & DBLSIZE ? y+1 : y, telemetryItem.text, sizeof(telemetryItem.text), att & ~DBLSIZE);
|
||||
}
|
||||
else {
|
||||
LcdFlags flags = att;
|
||||
if (telemetrySensor.prec > 0) {
|
||||
flags |= (telemetrySensor.prec==1 ? PREC1 : PREC2);
|
||||
}
|
||||
putsValueWithUnit(x, y, value, telemetrySensor.unit == UNIT_CELLS ? UNIT_VOLTS : telemetrySensor.unit, flags);
|
||||
}
|
||||
}
|
||||
|
||||
void putsChannelValue(coord_t x, coord_t y, source_t channel, int32_t value, LcdFlags att)
|
||||
{
|
||||
if (channel >= MIXSRC_FIRST_TELEM) {
|
||||
channel = (channel-MIXSRC_FIRST_TELEM) / 3;
|
||||
putsTelemetryChannelValue(x, y, channel, value, att);
|
||||
}
|
||||
else if (channel >= MIXSRC_FIRST_TIMER || channel == MIXSRC_TX_TIME) {
|
||||
drawTimer(x, y, value, att, att);
|
||||
}
|
||||
else if (channel == MIXSRC_TX_VOLTAGE) {
|
||||
lcdDrawNumber(x, y, value, att|PREC1);
|
||||
}
|
||||
else if (channel < MIXSRC_FIRST_CH) {
|
||||
lcdDrawNumber(x, y, calcRESXto100(value), att);
|
||||
}
|
||||
else if (channel <= MIXSRC_LAST_CH) {
|
||||
#if defined(PPM_UNIT_PERCENT_PREC1)
|
||||
lcdDrawNumber(x, y, calcRESXto1000(value), att|PREC1);
|
||||
#else
|
||||
lcdDrawNumber(x, y, calcRESXto100(value), att);
|
||||
#endif
|
||||
}
|
||||
else {
|
||||
lcdDrawNumber(x, y, value, att);
|
||||
}
|
||||
}
|
||||
|
||||
void putsChannel(coord_t x, coord_t y, source_t channel, LcdFlags att)
|
||||
{
|
||||
getvalue_t value = getValue(channel);
|
||||
putsChannelValue(x, y, channel, value, att);
|
||||
}
|
||||
|
||||
void lcdSetContrast()
|
||||
{
|
||||
lcdSetRefVolt(g_eeGeneral.contrast);
|
||||
|
|
|
@ -140,15 +140,19 @@ void putsVolts(coord_t x, coord_t y, uint16_t volts, LcdFlags att);
|
|||
void putsVBat(coord_t x, coord_t y, LcdFlags att);
|
||||
|
||||
#if !defined(BOOT)
|
||||
void putsChannelValue(coord_t x, coord_t y, source_t channel, int32_t val, LcdFlags att=0);
|
||||
void putsChannel(coord_t x, coord_t y, source_t channel, LcdFlags att=0);
|
||||
void putsTelemetryChannelValue(coord_t x, coord_t y, uint8_t channel, int32_t val, LcdFlags att=0);
|
||||
void drawSourceCustomValue(coord_t x, coord_t y, source_t channel, int32_t val, LcdFlags att=0);
|
||||
void drawSourceValue(coord_t x, coord_t y, source_t channel, LcdFlags flags=0);
|
||||
void drawSensorCustomValue(coord_t x, coord_t y, uint8_t source, int32_t val, LcdFlags att=0);
|
||||
#endif
|
||||
|
||||
#define putstime_t int32_t
|
||||
|
||||
void drawRtcTime(coord_t x, coord_t y, LcdFlags att);
|
||||
void drawTimer(coord_t x, coord_t y, putstime_t tme, LcdFlags att, LcdFlags att2);
|
||||
inline void drawTimer(coord_t x, coord_t y, putstime_t tme, LcdFlags att)
|
||||
{
|
||||
drawTimer(x, y, tme, att, att);
|
||||
}
|
||||
|
||||
#define SOLID 0xff
|
||||
#define DOTTED 0x55
|
||||
|
|
|
@ -201,12 +201,12 @@ void menuModelDisplay(uint8_t event)
|
|||
int barMin = -barMax;
|
||||
if (barSource) {
|
||||
if (barSource <= MIXSRC_LAST_CH) {
|
||||
putsChannelValue(DISPLAY_COL2, y, barSource, calc100toRESX(bar.barMin), (menuHorizontalPosition==1 ? attr : 0) | LEFT);
|
||||
putsChannelValue(DISPLAY_COL3, y, barSource, calc100toRESX(bar.barMax), (menuHorizontalPosition==2 ? attr : 0) | LEFT);
|
||||
drawSourceCustomValue(DISPLAY_COL2, y, barSource, calc100toRESX(bar.barMin), (menuHorizontalPosition==1 ? attr : 0) | LEFT);
|
||||
drawSourceCustomValue(DISPLAY_COL3, y, barSource, calc100toRESX(bar.barMax), (menuHorizontalPosition==2 ? attr : 0) | LEFT);
|
||||
}
|
||||
else {
|
||||
putsChannelValue(DISPLAY_COL2, y, barSource, bar.barMin, (menuHorizontalPosition==1 ? attr : 0) | LEFT);
|
||||
putsChannelValue(DISPLAY_COL3, y, barSource, bar.barMax, (menuHorizontalPosition==2 ? attr : 0) | LEFT);
|
||||
drawSourceCustomValue(DISPLAY_COL2, y, barSource, bar.barMin, (menuHorizontalPosition==1 ? attr : 0) | LEFT);
|
||||
drawSourceCustomValue(DISPLAY_COL3, y, barSource, bar.barMax, (menuHorizontalPosition==2 ? attr : 0) | LEFT);
|
||||
}
|
||||
}
|
||||
else if (attr) {
|
||||
|
|
|
@ -220,7 +220,7 @@ void menuModelExpoOne(uint8_t event)
|
|||
|
||||
case EXPO_FIELD_SCALE:
|
||||
lcdDrawTextAlignedLeft(y, STR_SCALE);
|
||||
putsTelemetryChannelValue(EXPO_ONE_2ND_COLUMN, y, (ed->srcRaw - MIXSRC_FIRST_TELEM)/3, convertTelemValue(ed->srcRaw - MIXSRC_FIRST_TELEM + 1, ed->scale), LEFT|attr);
|
||||
drawSensorCustomValue(EXPO_ONE_2ND_COLUMN, y, (ed->srcRaw - MIXSRC_FIRST_TELEM)/3, convertTelemValue(ed->srcRaw - MIXSRC_FIRST_TELEM + 1, ed->scale), LEFT|attr);
|
||||
if (attr) ed->scale = checkIncDec(event, ed->scale, 0, maxTelemValue(ed->srcRaw - MIXSRC_FIRST_TELEM + 1), EE_MODEL);
|
||||
break;
|
||||
|
||||
|
@ -271,7 +271,7 @@ void menuModelExpoOne(uint8_t event)
|
|||
|
||||
int x512 = getValue(ed->srcRaw);
|
||||
if (ed->srcRaw >= MIXSRC_FIRST_TELEM) {
|
||||
putsTelemetryChannelValue(LCD_W-8, 6*FH, (ed->srcRaw - MIXSRC_FIRST_TELEM) / 3, x512, 0);
|
||||
drawSensorCustomValue(LCD_W-8, 6*FH, (ed->srcRaw - MIXSRC_FIRST_TELEM) / 3, x512, 0);
|
||||
if (ed->scale > 0) x512 = (x512 * 1024) / convertTelemValue(ed->srcRaw - MIXSRC_FIRST_TELEM + 1, ed->scale);
|
||||
}
|
||||
else {
|
||||
|
|
|
@ -171,10 +171,10 @@ void menuModelLogicalSwitches(uint8_t event)
|
|||
v2_max = getMaximumValue(v1_val);
|
||||
v2_min = - v2_max;
|
||||
if (v1_val <= MIXSRC_LAST_CH) {
|
||||
putsChannelValue(CSW_3RD_COLUMN, y, v1_val, calc100toRESX(cs->v2), LEFT|attr2);
|
||||
drawSourceCustomValue(CSW_3RD_COLUMN, y, v1_val, calc100toRESX(cs->v2), LEFT|attr2);
|
||||
}
|
||||
else {
|
||||
putsChannelValue(CSW_3RD_COLUMN, y, v1_val, cs->v2, LEFT|attr2);
|
||||
drawSourceCustomValue(CSW_3RD_COLUMN, y, v1_val, cs->v2, LEFT|attr2);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -127,7 +127,7 @@ void menuModelSensor(uint8_t event)
|
|||
TelemetrySensor * sensor = &g_model.telemetrySensors[s_currIdx];
|
||||
|
||||
drawStringWithIndex(PSIZE(TR_MENUSENSOR)*FW+FW, 0, STR_SENSOR, s_currIdx+1);
|
||||
putsTelemetryChannelValue(25*FW, 0, s_currIdx, getValue(MIXSRC_FIRST_TELEM+3*s_currIdx));
|
||||
drawSensorCustomValue(25*FW, 0, s_currIdx, getValue(MIXSRC_FIRST_TELEM+3*s_currIdx));
|
||||
lcdDrawFilledRect(0, 0, LCD_W, FH, SOLID, FILL_WHITE|GREY_DEFAULT);
|
||||
|
||||
SUBMENU(STR_MENUSENSOR, SENSOR_FIELD_MAX, { 0, 0, sensor->type == TELEM_TYPE_CALCULATED ? (uint8_t)0 : (uint8_t)1, SENSOR_UNIT_ROWS, SENSOR_PREC_ROWS, SENSOR_PARAM1_ROWS, SENSOR_PARAM2_ROWS, SENSOR_PARAM3_ROWS, SENSOR_PARAM4_ROWS, SENSOR_AUTOOFFSET_ROWS, SENSOR_ONLYPOS_ROWS, SENSOR_FILTER_ROWS, SENSOR_PERSISTENT_ROWS, 0 });
|
||||
|
@ -426,7 +426,7 @@ void menuModelTelemetryFrsky(uint8_t event)
|
|||
bool isOld = telemetryItem.isOld();
|
||||
lcdNextPos = TELEM_COL2;
|
||||
if (isOld) lcdDrawChar(lcdNextPos, y, '[');
|
||||
putsTelemetryChannelValue(lcdNextPos, y, index, getValue(MIXSRC_FIRST_TELEM+3*index), LEFT);
|
||||
drawSensorCustomValue(lcdNextPos, y, index, getValue(MIXSRC_FIRST_TELEM+3*index), LEFT);
|
||||
if (isOld) lcdDrawChar(lcdLastPos, y, ']');
|
||||
}
|
||||
else {
|
||||
|
|
|
@ -223,7 +223,7 @@ void displayTopBar()
|
|||
if (item < MAX_TELEMETRY_SENSORS) {
|
||||
TelemetryItem & voltsItem = telemetryItems[item];
|
||||
if (voltsItem.isAvailable()) {
|
||||
putsTelemetryChannelValue(batt_icon_x+7*FW+2, BAR_Y+1, item, voltsItem.value, LEFT);
|
||||
drawSensorCustomValue(batt_icon_x+7*FW+2, BAR_Y+1, item, voltsItem.value, LEFT);
|
||||
altitude_icon_x = lcdLastPos+1;
|
||||
}
|
||||
}
|
||||
|
@ -237,7 +237,7 @@ void displayTopBar()
|
|||
if (altitudeItem.isAvailable()) {
|
||||
LCD_ICON(altitude_icon_x, BAR_Y, ICON_ALTITUDE);
|
||||
int32_t value = altitudeItem.value / g_model.telemetrySensors[item].getPrecDivisor();
|
||||
putsValueWithUnit(altitude_icon_x+2*FW-1, BAR_Y+1, value, g_model.telemetrySensors[item].unit, LEFT);
|
||||
drawValueWithUnit(altitude_icon_x+2*FW-1, BAR_Y+1, value, g_model.telemetrySensors[item].unit, LEFT);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -72,7 +72,7 @@ void displayGaugesTelemetryScreen(FrSkyScreenData & screen)
|
|||
drawSource(0, y+barHeight-5, source, 0);
|
||||
lcdDrawRect(BAR_LEFT, y, BAR_WIDTH+1, barHeight+2);
|
||||
getvalue_t value = getValue(source);
|
||||
putsChannel(BAR_LEFT+2+BAR_WIDTH, y+barHeight-5, source, LEFT);
|
||||
drawSourceValue(BAR_LEFT+2+BAR_WIDTH, y+barHeight-5, source, LEFT);
|
||||
uint8_t thresholdX = 0;
|
||||
int width = barCoord(value, barMin, barMax);
|
||||
uint8_t barShade = SOLID;
|
||||
|
@ -143,7 +143,7 @@ bool displayNumbersTelemetryScreen(FrSkyScreenData & screen)
|
|||
}
|
||||
}
|
||||
|
||||
putsChannel(x, y, field, att);
|
||||
drawSourceValue(x, y, field, att);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -178,7 +178,7 @@ void drawGVarValue(coord_t x, coord_t y, uint8_t gvar, gvar_t value, LcdFlags fl
|
|||
if (prec > 0) {
|
||||
flags |= (prec == 1 ? PREC1 : PREC2);
|
||||
}
|
||||
putsValueWithUnit(x, y, value, g_model.gvars[gvar].unit ? UNIT_PERCENT : UNIT_RAW, flags);
|
||||
drawValueWithUnit(x, y, value, g_model.gvars[gvar].unit ? UNIT_PERCENT : UNIT_RAW, flags);
|
||||
}
|
||||
|
||||
int16_t editGVarFieldValue(coord_t x, coord_t y, int16_t value, int16_t min, int16_t max, LcdFlags attr, uint8_t editflags, uint8_t event)
|
||||
|
|
|
@ -340,7 +340,7 @@ const pm_uint8_t bchunit_ar[] PROGMEM = {
|
|||
UNIT_DIST, // GPS Alt
|
||||
};
|
||||
|
||||
void putsValueWithUnit(coord_t x, coord_t y, int32_t val, uint8_t unit, LcdFlags att)
|
||||
void drawValueWithUnit(coord_t x, coord_t y, int32_t val, uint8_t unit, LcdFlags att)
|
||||
{
|
||||
// convertUnit(val, unit);
|
||||
if (!(att & NO_UNIT) && unit != UNIT_RAW) {
|
||||
|
@ -353,66 +353,78 @@ void putsValueWithUnit(coord_t x, coord_t y, int32_t val, uint8_t unit, LcdFlags
|
|||
}
|
||||
}
|
||||
|
||||
void displayDate(coord_t x, coord_t y, TelemetryItem & telemetryItem, LcdFlags att)
|
||||
void drawDate(coord_t x, coord_t y, TelemetryItem & telemetryItem, LcdFlags att)
|
||||
{
|
||||
}
|
||||
|
||||
void displayGpsCoords(coord_t x, coord_t y, TelemetryItem & telemetryItem, LcdFlags att)
|
||||
{
|
||||
}
|
||||
|
||||
void putsTelemetryChannelValue(coord_t x, coord_t y, uint8_t channel, int32_t value, LcdFlags att)
|
||||
{
|
||||
TelemetryItem & telemetryItem = telemetryItems[channel];
|
||||
TelemetrySensor & telemetrySensor = g_model.telemetrySensors[channel];
|
||||
|
||||
if (telemetrySensor.unit == UNIT_DATETIME) {
|
||||
displayDate(x, y, telemetryItem, att);
|
||||
}
|
||||
else if (telemetrySensor.unit == UNIT_GPS) {
|
||||
displayGpsCoords(x, y, telemetryItem, att);
|
||||
if (att & DBLSIZE) {
|
||||
x -= 42;
|
||||
att &= ~0x0F00; // TODO constant
|
||||
lcdDrawNumber(x, y, telemetryItem.datetime.day, att|LEADING0|LEFT, 2);
|
||||
lcdDrawChar(lcdNextPos-1, y, '-', att);
|
||||
lcdDrawNumber(lcdNextPos-1, y, telemetryItem.datetime.month, att|LEFT, 2);
|
||||
lcdDrawChar(lcdNextPos-1, y, '-', att);
|
||||
lcdDrawNumber(lcdNextPos-1, y, telemetryItem.datetime.year, att|LEFT);
|
||||
y += FH;
|
||||
lcdDrawNumber(x, y, telemetryItem.datetime.hour, att|LEADING0|LEFT, 2);
|
||||
lcdDrawChar(lcdNextPos, y, ':', att);
|
||||
lcdDrawNumber(lcdNextPos, y, telemetryItem.datetime.min, att|LEADING0|LEFT, 2);
|
||||
lcdDrawChar(lcdNextPos, y, ':', att);
|
||||
lcdDrawNumber(lcdNextPos, y, telemetryItem.datetime.sec, att|LEADING0|LEFT, 2);
|
||||
}
|
||||
else {
|
||||
LcdFlags flags = att;
|
||||
if (telemetrySensor.prec==2)
|
||||
flags |= PREC2;
|
||||
else if (telemetrySensor.prec==1)
|
||||
flags |= PREC1;
|
||||
putsValueWithUnit(x, y, value, telemetrySensor.unit == UNIT_CELLS ? UNIT_VOLTS : telemetrySensor.unit, flags);
|
||||
lcdDrawNumber(x, y, telemetryItem.datetime.day, att|LEADING0|LEFT, 2);
|
||||
lcdDrawChar(lcdNextPos-1, y, '-', att);
|
||||
lcdDrawNumber(lcdNextPos, y, telemetryItem.datetime.month, att|LEFT, 2);
|
||||
lcdDrawChar(lcdNextPos-1, y, '-', att);
|
||||
lcdDrawNumber(lcdNextPos, y, telemetryItem.datetime.year, att|LEFT);
|
||||
lcdDrawNumber(lcdNextPos+11, y, telemetryItem.datetime.hour, att|LEADING0|LEFT, 2);
|
||||
lcdDrawChar(lcdNextPos, y, ':', att);
|
||||
lcdDrawNumber(lcdNextPos, y, telemetryItem.datetime.min, att|LEADING0|LEFT, 2);
|
||||
lcdDrawChar(lcdNextPos, y, ':', att);
|
||||
lcdDrawNumber(lcdNextPos, y, telemetryItem.datetime.sec, att|LEADING0|LEFT, 2);
|
||||
}
|
||||
}
|
||||
|
||||
void putsChannelValue(coord_t x, coord_t y, source_t channel, int32_t value, LcdFlags att)
|
||||
void drawGPSCoord(coord_t x, coord_t y, int32_t value, const char * direction, LcdFlags flags, bool seconds=true)
|
||||
{
|
||||
if (channel >= MIXSRC_FIRST_TELEM) {
|
||||
channel = (channel-MIXSRC_FIRST_TELEM) / 3;
|
||||
putsTelemetryChannelValue(x, y, channel, value, att);
|
||||
char s[32];
|
||||
uint32_t absvalue = abs(value);
|
||||
char * tmp = strAppendUnsigned(s, absvalue / 1000000);
|
||||
*tmp++ = '@';
|
||||
absvalue = absvalue % 1000000;
|
||||
absvalue *= 60;
|
||||
if (g_eeGeneral.gpsFormat == 0 || !seconds) {
|
||||
tmp = strAppendUnsigned(tmp, absvalue / 1000000, 2);
|
||||
*tmp++ = '\'';
|
||||
if (seconds) {
|
||||
absvalue %= 1000000;
|
||||
absvalue *= 60;
|
||||
absvalue /= 100000;
|
||||
tmp = strAppendUnsigned(tmp, absvalue / 10);
|
||||
*tmp++ = '.';
|
||||
tmp = strAppendUnsigned(tmp, absvalue % 10);
|
||||
*tmp++ = '"';
|
||||
}
|
||||
else if (channel >= MIXSRC_FIRST_TIMER || channel == MIXSRC_TX_TIME) {
|
||||
drawTimer(x, y, value, att);
|
||||
}
|
||||
else if (channel == MIXSRC_TX_VOLTAGE) {
|
||||
lcdDrawNumber(x, y, value, att|PREC1);
|
||||
}
|
||||
else if (channel < MIXSRC_FIRST_CH) {
|
||||
lcdDrawNumber(x, y, calcRESXto100(value), att);
|
||||
}
|
||||
else if (channel <= MIXSRC_LAST_CH) {
|
||||
#if defined(PPM_UNIT_PERCENT_PREC1)
|
||||
lcdDrawNumber(x, y, calcRESXto1000(value), att|PREC1);
|
||||
#else
|
||||
lcdDrawNumber(x, y, calcRESXto100(value), att);
|
||||
#endif
|
||||
}
|
||||
else {
|
||||
lcdDrawNumber(x, y, value, att);
|
||||
tmp = strAppendUnsigned(tmp, absvalue / 1000000, 2);
|
||||
*tmp++ = '.';
|
||||
absvalue /= 1000;
|
||||
tmp = strAppendUnsigned(tmp, absvalue, 3);
|
||||
}
|
||||
*tmp++ = direction[value>=0 ? 0 : 1];
|
||||
*tmp = '\0';
|
||||
lcdDrawText(x, y, s, flags);
|
||||
}
|
||||
|
||||
void putsChannel(coord_t x, coord_t y, source_t channel, LcdFlags att)
|
||||
void drawGPSPosition(coord_t x, coord_t y, int32_t longitude, int32_t latitude, LcdFlags flags)
|
||||
{
|
||||
getvalue_t value = getValue(channel);
|
||||
putsChannelValue(x, y, channel, value, att);
|
||||
drawGPSCoord(x, y, longitude, "EW", flags);
|
||||
drawGPSCoord(x, y+FH, latitude, "NS", flags);
|
||||
}
|
||||
|
||||
void drawGPSSensorValue(coord_t x, coord_t y, TelemetryItem & telemetryItem, LcdFlags flags)
|
||||
{
|
||||
drawGPSPosition(x, y, telemetryItem.gps.longitude, telemetryItem.gps.latitude, flags);
|
||||
}
|
||||
|
||||
void lcdSetContrast()
|
||||
|
|
|
@ -141,9 +141,9 @@ void drawTrimMode(coord_t x, coord_t y, uint8_t phase, uint8_t idx, LcdFlags att
|
|||
#define putsChn(x, y, idx, att) drawSource(x, y, MIXSRC_CH1+idx-1, att)
|
||||
void putsChnLetter(coord_t x, coord_t y, uint8_t idx, LcdFlags attr);
|
||||
|
||||
void putsChannelValue(coord_t x, coord_t y, source_t channel, int32_t val, LcdFlags att=0);
|
||||
void putsChannel(coord_t x, coord_t y, source_t channel, LcdFlags att=0);
|
||||
void putsTelemetryChannelValue(coord_t x, coord_t y, uint8_t channel, int32_t val, LcdFlags att=0);
|
||||
void drawSourceCustomValue(coord_t x, coord_t y, source_t channel, int32_t val, LcdFlags att=0);
|
||||
void drawSourceValue(coord_t x, coord_t y, source_t channel, LcdFlags att=0);
|
||||
void drawSensorCustomValue(coord_t x, coord_t y, uint8_t channel, int32_t val, LcdFlags att=0);
|
||||
|
||||
#define putstime_t int32_t
|
||||
|
||||
|
|
|
@ -193,7 +193,7 @@ bool menuModelExpoOne(event_t event)
|
|||
int x = getValue(ed->srcRaw);
|
||||
if (ed->srcRaw >= MIXSRC_FIRST_TELEM) {
|
||||
strAppendUnsigned(textx, calcRESXto100(x));
|
||||
// TODO putsTelemetryChannelValue(LCD_W-8, 6*FH, ed->srcRaw - MIXSRC_FIRST_TELEM, x);
|
||||
// TODO drawSensorCustomValue(LCD_W-8, 6*FH, ed->srcRaw - MIXSRC_FIRST_TELEM, x);
|
||||
if (ed->scale > 0) x = (x * 1024) / convertTelemValue(ed->srcRaw - MIXSRC_FIRST_TELEM + 1, ed->scale);
|
||||
}
|
||||
else {
|
||||
|
@ -236,7 +236,7 @@ bool menuModelExpoOne(event_t event)
|
|||
drawSource(EXPO_ONE_2ND_COLUMN, y, ed->srcRaw, menuHorizontalPosition==0 ? attr : 0);
|
||||
if (attr && menuHorizontalPosition==0) ed->srcRaw = checkIncDec(event, ed->srcRaw, INPUTSRC_FIRST, INPUTSRC_LAST, EE_MODEL|INCDEC_SOURCE|NO_INCDEC_MARKS, isInputSourceAvailable);
|
||||
if (ed->srcRaw >= MIXSRC_FIRST_TELEM) {
|
||||
putsTelemetryChannelValue(EXPO_ONE_2ND_COLUMN+60, y, (ed->srcRaw - MIXSRC_FIRST_TELEM)/3, convertTelemValue(ed->srcRaw - MIXSRC_FIRST_TELEM + 1, ed->scale), LEFT|(menuHorizontalPosition==1?attr:0));
|
||||
drawSensorCustomValue(EXPO_ONE_2ND_COLUMN+60, y, (ed->srcRaw - MIXSRC_FIRST_TELEM)/3, convertTelemValue(ed->srcRaw - MIXSRC_FIRST_TELEM + 1, ed->scale), LEFT|(menuHorizontalPosition==1?attr:0));
|
||||
if (attr && menuHorizontalPosition == 1) ed->scale = checkIncDec(event, ed->scale, 0, maxTelemValue(ed->srcRaw - MIXSRC_FIRST_TELEM + 1), EE_MODEL);
|
||||
}
|
||||
else if (attr) {
|
||||
|
|
|
@ -172,7 +172,7 @@ bool menuModelLogicalSwitches(event_t event)
|
|||
}
|
||||
v2_max = getMaximumValue(v1_val);
|
||||
v2_min = - v2_max;
|
||||
putsChannelValue(CSW_3RD_COLUMN, y, v1_val, v1_val <= MIXSRC_LAST_CH ? calc100toRESX(cs->v2) : cs->v2, LEFT|attr2);
|
||||
drawSourceCustomValue(CSW_3RD_COLUMN, y, v1_val, v1_val <= MIXSRC_LAST_CH ? calc100toRESX(cs->v2) : cs->v2, LEFT|attr2);
|
||||
}
|
||||
|
||||
// CSW AND switch
|
||||
|
|
|
@ -129,7 +129,7 @@ bool menuModelSensor(event_t event)
|
|||
|
||||
SUBMENU("SENSOR", ICON_MODEL_TELEMETRY, SENSOR_FIELD_MAX, { 0, 0, sensor->type == TELEM_TYPE_CALCULATED ? (uint8_t)0 : (uint8_t)1, SENSOR_UNIT_ROWS, SENSOR_PREC_ROWS, SENSOR_PARAM1_ROWS, SENSOR_PARAM2_ROWS, SENSOR_PARAM3_ROWS, SENSOR_PARAM4_ROWS, 0, 0, 0, 0, 0 });
|
||||
lcdDrawNumber(lcdNextPos, 3, s_currIdx+1, MENU_TITLE_COLOR|LEFT);
|
||||
putsTelemetryChannelValue(50, 3+FH, s_currIdx, getValue(MIXSRC_FIRST_TELEM+3*s_currIdx), MENU_TITLE_COLOR|LEFT);
|
||||
drawSensorCustomValue(50, 3+FH, s_currIdx, getValue(MIXSRC_FIRST_TELEM+3*s_currIdx), MENU_TITLE_COLOR|LEFT);
|
||||
|
||||
for (unsigned int i=0; i<NUM_BODY_LINES+1; i++) {
|
||||
coord_t y = MENU_CONTENT_TOP - FH - 2 + i*FH;
|
||||
|
@ -430,7 +430,7 @@ bool menuModelTelemetryFrsky(event_t event)
|
|||
}
|
||||
if (telemetryItem.isAvailable()) {
|
||||
LcdFlags color = telemetryItem.isOld() ? ALARM_COLOR : TEXT_COLOR;
|
||||
putsTelemetryChannelValue(TELEM_COL2, y, index, getValue(MIXSRC_FIRST_TELEM+3*index), LEFT|color);
|
||||
drawSensorCustomValue(TELEM_COL2, y, index, getValue(MIXSRC_FIRST_TELEM+3*index), LEFT|color);
|
||||
}
|
||||
else {
|
||||
lcdDrawText(TELEM_COL2, y, "---"); // TODO shortcut
|
||||
|
|
|
@ -325,7 +325,7 @@ bool menuRadioSetup(event_t event)
|
|||
|
||||
case ITEM_SETUP_BATTERY_WARNING:
|
||||
lcdDrawText(MENUS_MARGIN_LEFT, y, STR_BATTERYWARNING);
|
||||
putsValueWithUnit(RADIO_SETUP_2ND_COLUMN, y, g_eeGeneral.vBatWarn, UNIT_VOLTS, attr|PREC1|LEFT);
|
||||
drawValueWithUnit(RADIO_SETUP_2ND_COLUMN, y, g_eeGeneral.vBatWarn, UNIT_VOLTS, attr|PREC1|LEFT);
|
||||
if (attr) CHECK_INCDEC_GENVAR(event, g_eeGeneral.vBatWarn, 40, 120); //4-12V
|
||||
break;
|
||||
|
||||
|
@ -350,7 +350,7 @@ bool menuRadioSetup(event_t event)
|
|||
#if defined(PCBSKY9X)
|
||||
case ITEM_SETUP_CAPACITY_WARNING:
|
||||
lcdDrawText(MENUS_MARGIN_LEFT, y, STR_CAPAWARNING);
|
||||
putsValueWithUnit(RADIO_SETUP_2ND_COLUMN, y, g_eeGeneral.mAhWarn*50, UNIT_MAH, attr|LEFT) ;
|
||||
drawValueWithUnit(RADIO_SETUP_2ND_COLUMN, y, g_eeGeneral.mAhWarn*50, UNIT_MAH, attr|LEFT) ;
|
||||
if (attr) CHECK_INCDEC_GENVAR(event, g_eeGeneral.mAhWarn, 0, 100);
|
||||
break;
|
||||
#endif
|
||||
|
@ -358,7 +358,7 @@ bool menuRadioSetup(event_t event)
|
|||
#if defined(PCBSKY9X)
|
||||
case ITEM_SETUP_TEMPERATURE_WARNING:
|
||||
lcdDrawText(MENUS_MARGIN_LEFT, y, STR_TEMPWARNING);
|
||||
putsValueWithUnit(RADIO_SETUP_2ND_COLUMN, y, g_eeGeneral.temperatureWarn, UNIT_TEMPERATURE, attr|LEFT) ;
|
||||
drawValueWithUnit(RADIO_SETUP_2ND_COLUMN, y, g_eeGeneral.temperatureWarn, UNIT_TEMPERATURE, attr|LEFT) ;
|
||||
if (attr) CHECK_INCDEC_GENVAR(event, g_eeGeneral.temperatureWarn, 0, 120); // 0 means no alarm
|
||||
break;
|
||||
#endif
|
||||
|
|
|
@ -92,7 +92,7 @@ void drawTopBar()
|
|||
|
||||
#if 0
|
||||
// Radio battery - TODO
|
||||
// putsValueWithUnit(370, 8, g_vbat100mV, UNIT_VOLTS, PREC1|SMLSIZE|MENU_TITLE_COLOR);
|
||||
// drawValueWithUnit(370, 8, g_vbat100mV, UNIT_VOLTS, PREC1|SMLSIZE|MENU_TITLE_COLOR);
|
||||
// lcdDrawSolidRect(300, 3, 20, 50, MENU_TITLE_COLOR);
|
||||
// lcdDrawRect(batt_icon_x+FW, BAR_Y+1, 13, 7);
|
||||
// lcdDrawSolidVerticalLine(batt_icon_x+FW+13, BAR_Y+2, 5);
|
||||
|
@ -114,7 +114,7 @@ void drawTopBar()
|
|||
att |= (item.isOld() ? ALARM_COLOR : TEXT_COLOR);
|
||||
lcdDrawSolidFilledRect(ALTITUDE_X, VOLTS_Y, ALTITUDE_W, ALTITUDE_H, TEXT_BGCOLOR);
|
||||
lcdDrawText(ALTITUDE_X+PADDING, VOLTS_Y+2, "Voltage", att);
|
||||
putsValueWithUnit(ALTITUDE_X+PADDING, VOLTS_Y+12, value, UNIT_VOLTS, DBLSIZE|LEFT|att);
|
||||
drawValueWithUnit(ALTITUDE_X+PADDING, VOLTS_Y+12, value, UNIT_VOLTS, DBLSIZE|LEFT|att);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -128,7 +128,7 @@ void drawTopBar()
|
|||
LcdFlags att = (item.isOld() ? ALARM_COLOR : TEXT_COLOR);
|
||||
lcdDrawSolidFilledRect(ALTITUDE_X, ALTITUDE_Y, ALTITUDE_W, ALTITUDE_H, TEXT_BGCOLOR);
|
||||
lcdDrawText(ALTITUDE_X+PADDING, ALTITUDE_Y+2, "Alt", att);
|
||||
putsValueWithUnit(ALTITUDE_X+PADDING, ALTITUDE_Y+12, value, UNIT_METERS, DBLSIZE|LEFT|att);
|
||||
drawValueWithUnit(ALTITUDE_X+PADDING, ALTITUDE_Y+12, value, UNIT_METERS, DBLSIZE|LEFT|att);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -63,7 +63,7 @@ void displayLogicalSwitchedDetails(coord_t x, coord_t y, uint8_t idx)
|
|||
}
|
||||
else {
|
||||
drawSource(CSW_2ND_COLUMN, y, cs->v1, 0);
|
||||
putsChannelValue(CSW_3RD_COLUMN, y, cs->v1, cs->v1 <= MIXSRC_LAST_CH ? calc100toRESX(cs->v2) : cs->v2, LEFT);
|
||||
drawSourceCustomValue(CSW_3RD_COLUMN, y, cs->v1, cs->v1 <= MIXSRC_LAST_CH ? calc100toRESX(cs->v2) : cs->v2, LEFT);
|
||||
}
|
||||
|
||||
// CSW AND switch
|
||||
|
|
|
@ -49,6 +49,8 @@ void ValueWidget::refresh()
|
|||
int x = zone.x;
|
||||
int y = zone.y;
|
||||
|
||||
// TRACE("w=%d, h=%d", zone.w, zone.h);
|
||||
|
||||
// lcdDrawFilledRect(zone.x, zone.y, zone.w, zone.h, SOLID, MAINVIEW_PANES_COLOR | OPACITY(5));
|
||||
|
||||
int xValue, yValue, xLabel, yLabel;
|
||||
|
@ -70,9 +72,12 @@ void ValueWidget::refresh()
|
|||
}
|
||||
else {
|
||||
xValue = x+NUMBERS_PADDING;
|
||||
yValue = y+16;
|
||||
yValue = y+18;
|
||||
xLabel = x+NUMBERS_PADDING;
|
||||
yLabel = y+2;
|
||||
if (field == MIXSRC_TX_GPS)
|
||||
attrValue = LEFT | MIDSIZE;
|
||||
else
|
||||
attrValue = LEFT | DBLSIZE;
|
||||
}
|
||||
|
||||
|
@ -96,8 +101,8 @@ void ValueWidget::refresh()
|
|||
|
||||
drawSource(xLabel + 1, yLabel + 1, field, attrLabel|BLACK);
|
||||
drawSource(xLabel, yLabel, field, attrLabel|CUSTOM_COLOR);
|
||||
putsChannel(xValue + 1, yValue + 1, field, attrValue|BLACK);
|
||||
putsChannel(xValue, yValue, field, attrValue|CUSTOM_COLOR);
|
||||
drawSourceValue(xValue + 1, yValue + 1, field, attrValue|BLACK);
|
||||
drawSourceValue(xValue, yValue, field, attrValue|CUSTOM_COLOR);
|
||||
|
||||
}
|
||||
|
||||
|
|
|
@ -1,7 +1,6 @@
|
|||
set(GUI_SRC
|
||||
${GUI_SRC}
|
||||
lcd.cpp
|
||||
../common/widgets.cpp
|
||||
splash.cpp
|
||||
fonts.cpp
|
||||
navigation.cpp
|
||||
|
@ -24,8 +23,20 @@ set(GUI_SRC
|
|||
view_statistics.cpp
|
||||
)
|
||||
|
||||
set(SRC
|
||||
${SRC}
|
||||
gui/common/widgets.cpp
|
||||
)
|
||||
|
||||
include_directories(gui gui/${GUI_DIR})
|
||||
|
||||
if(GUI_DIR STREQUAL 128x64 OR GUI_DIR STREQUAL 212x64)
|
||||
include(gui/common/stdlcd/CMakeLists.txt)
|
||||
endif()
|
||||
|
||||
if(ARCH STREQUAL ARM)
|
||||
set(SRC
|
||||
${SRC}
|
||||
gui/common/arm/widgets.cpp
|
||||
)
|
||||
endif()
|
||||
|
|
161
radio/src/gui/common/arm/widgets.cpp
Normal file
161
radio/src/gui/common/arm/widgets.cpp
Normal file
|
@ -0,0 +1,161 @@
|
|||
/*
|
||||
* Copyright (C) OpenTX
|
||||
*
|
||||
* Based on code named
|
||||
* th9x - http://code.google.com/p/th9x
|
||||
* er9x - http://code.google.com/p/er9x
|
||||
* gruvin9x - http://code.google.com/p/gruvin9x
|
||||
*
|
||||
* License GPLv2: http://www.gnu.org/licenses/gpl-2.0.html
|
||||
*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License version 2 as
|
||||
* published by the Free Software Foundation.
|
||||
*
|
||||
* 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.
|
||||
*/
|
||||
|
||||
#include "opentx.h"
|
||||
|
||||
void drawCurveRef(coord_t x, coord_t y, CurveRef & curve, LcdFlags att)
|
||||
{
|
||||
if (curve.value != 0) {
|
||||
switch (curve.type) {
|
||||
case CURVE_REF_DIFF:
|
||||
lcdDrawText(x, y, "D", att);
|
||||
GVAR_MENU_ITEM(lcdNextPos, y, curve.value, -100, 100, LEFT|att, 0, 0);
|
||||
break;
|
||||
|
||||
case CURVE_REF_EXPO:
|
||||
lcdDrawText(x, y, "E", att);
|
||||
GVAR_MENU_ITEM(lcdNextPos, y, curve.value, -100, 100, LEFT|att, 0, 0);
|
||||
break;
|
||||
|
||||
case CURVE_REF_FUNC:
|
||||
lcdDrawTextAtIndex(x, y, STR_VCURVEFUNC, curve.value, att);
|
||||
break;
|
||||
|
||||
case CURVE_REF_CUSTOM:
|
||||
drawCurveName(x, y, curve.value, att);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void drawSensorCustomValue(coord_t x, coord_t y, uint8_t sensor, int32_t value, LcdFlags flags)
|
||||
{
|
||||
if (sensor >= MAX_TELEMETRY_SENSORS) {
|
||||
// Lua luaLcdDrawChannel() can call us with a bad value
|
||||
return;
|
||||
}
|
||||
|
||||
TelemetryItem & telemetryItem = telemetryItems[sensor];
|
||||
TelemetrySensor & telemetrySensor = g_model.telemetrySensors[sensor];
|
||||
|
||||
if (telemetrySensor.unit == UNIT_DATETIME) {
|
||||
drawDate(x, y, telemetryItem, flags);
|
||||
}
|
||||
else if (telemetrySensor.unit == UNIT_GPS) {
|
||||
drawGPSSensorValue(x, y, telemetryItem, flags);
|
||||
}
|
||||
else if (telemetrySensor.unit == UNIT_BITFIELD) {
|
||||
if (IS_FRSKY_SPORT_PROTOCOL()) {
|
||||
if (telemetrySensor.id >= RBOX_STATE_FIRST_ID && telemetrySensor.id <= RBOX_STATE_LAST_ID) {
|
||||
if (telemetrySensor.subId == 0) {
|
||||
if (value == 0) {
|
||||
lcdDrawText(x, y, "OK", flags);
|
||||
}
|
||||
else {
|
||||
for (uint8_t i=0; i<16; i++) {
|
||||
if (value & (1 << i)) {
|
||||
char s[] = "CH__ KO";
|
||||
strAppendUnsigned(&s[2], i+1, 2);
|
||||
lcdDrawText(x, flags & DBLSIZE ? y+1 : y, s, flags & ~DBLSIZE);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else {
|
||||
if (value == 0) {
|
||||
lcdDrawText(x, flags & DBLSIZE ? y+1 : y, "Rx OK", flags & ~DBLSIZE);
|
||||
}
|
||||
else {
|
||||
static const char * const RXS_STATUS[] = {
|
||||
"Rx1 Ovl",
|
||||
"Rx2 Ovl",
|
||||
"SBUS Ovl",
|
||||
"Rx1 FS",
|
||||
"Rx1 LF",
|
||||
"Rx2 FS",
|
||||
"Rx2 LF",
|
||||
"Rx1 Lost",
|
||||
"Rx2 Lost",
|
||||
"Rx1 NS",
|
||||
"Rx2 NS",
|
||||
};
|
||||
for (uint8_t i=0; i<DIM(RXS_STATUS); i++) {
|
||||
if (value & (1<<i)) {
|
||||
lcdDrawText(x, flags & DBLSIZE ? y+1 : y, RXS_STATUS[i], flags & ~DBLSIZE);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else if (telemetrySensor.unit == UNIT_TEXT) {
|
||||
lcdDrawSizedText(x, flags & DBLSIZE ? y+1 : y, telemetryItem.text, sizeof(telemetryItem.text), flags & ~DBLSIZE);
|
||||
}
|
||||
else {
|
||||
if (telemetrySensor.prec > 0) {
|
||||
flags |= (telemetrySensor.prec==1 ? PREC1 : PREC2);
|
||||
}
|
||||
drawValueWithUnit(x, y, value, telemetrySensor.unit == UNIT_CELLS ? UNIT_VOLTS : telemetrySensor.unit, flags);
|
||||
}
|
||||
}
|
||||
|
||||
void drawSourceCustomValue(coord_t x, coord_t y, source_t source, int32_t value, LcdFlags flags)
|
||||
{
|
||||
if (source >= MIXSRC_FIRST_TELEM) {
|
||||
source = (source-MIXSRC_FIRST_TELEM) / 3;
|
||||
drawSensorCustomValue(x, y, source, value, flags);
|
||||
}
|
||||
else if (source >= MIXSRC_FIRST_TIMER || source == MIXSRC_TX_TIME) {
|
||||
drawTimer(x, y, value, flags);
|
||||
}
|
||||
else if (source == MIXSRC_TX_VOLTAGE) {
|
||||
lcdDrawNumber(x, y, value, flags|PREC1);
|
||||
}
|
||||
#if defined(INTERNAL_GPS)
|
||||
else if (source == MIXSRC_TX_GPS) {
|
||||
if (gpsData.fix) {
|
||||
drawGPSPosition(x, y, gpsData.longitude, gpsData.latitude, flags);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
else if (source < MIXSRC_FIRST_CH) {
|
||||
lcdDrawNumber(x, y, calcRESXto100(value), flags);
|
||||
}
|
||||
else if (source <= MIXSRC_LAST_CH) {
|
||||
#if defined(PPM_UNIT_PERCENT_PREC1)
|
||||
lcdDrawNumber(x, y, calcRESXto1000(value), flags|PREC1);
|
||||
#else
|
||||
lcdDrawNumber(x, y, calcRESXto100(value), flags);
|
||||
#endif
|
||||
}
|
||||
else {
|
||||
lcdDrawNumber(x, y, value, flags);
|
||||
}
|
||||
}
|
||||
|
||||
void drawSourceValue(coord_t x, coord_t y, source_t source, LcdFlags flags)
|
||||
{
|
||||
getvalue_t value = getValue(source);
|
||||
drawSourceCustomValue(x, y, source, value, flags);
|
||||
}
|
||||
|
|
@ -42,29 +42,3 @@ void drawFlightMode(coord_t x, coord_t y, int8_t idx, LcdFlags att)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if defined(CPUARM)
|
||||
void drawCurveRef(coord_t x, coord_t y, CurveRef & curve, LcdFlags att)
|
||||
{
|
||||
if (curve.value != 0) {
|
||||
switch (curve.type) {
|
||||
case CURVE_REF_DIFF:
|
||||
lcdDrawText(x, y, "D", att);
|
||||
GVAR_MENU_ITEM(lcdNextPos, y, curve.value, -100, 100, LEFT|att, 0, 0);
|
||||
break;
|
||||
|
||||
case CURVE_REF_EXPO:
|
||||
lcdDrawText(x, y, "E", att);
|
||||
GVAR_MENU_ITEM(lcdNextPos, y, curve.value, -100, 100, LEFT|att, 0, 0);
|
||||
break;
|
||||
|
||||
case CURVE_REF_FUNC:
|
||||
lcdDrawTextAtIndex(x, y, STR_VCURVEFUNC, curve.value, att);
|
||||
break;
|
||||
|
||||
case CURVE_REF_CUSTOM:
|
||||
drawCurveName(x, y, curve.value, att);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -78,7 +78,11 @@ void drawFlightMode(coord_t x, coord_t y, int8_t idx, LcdFlags att=0);
|
|||
#endif
|
||||
|
||||
#if defined(CPUARM)
|
||||
#include "telemetry/telemetry_sensors.h"
|
||||
void drawCurveRef(coord_t x, coord_t y, CurveRef & curve, LcdFlags att=0);
|
||||
void drawDate(coord_t x, coord_t y, TelemetryItem & telemetryItem, LcdFlags att);
|
||||
void drawGPSPosition(coord_t x, coord_t y, int32_t longitude, int32_t latitude, LcdFlags flags);
|
||||
void drawGPSSensorValue(coord_t x, coord_t y, TelemetryItem & telemetryItem, LcdFlags flags);
|
||||
#endif
|
||||
|
||||
void drawCurve(coord_t offset=0);
|
||||
|
|
|
@ -188,7 +188,7 @@ bool isSourceAvailable(int source)
|
|||
return false;
|
||||
#endif
|
||||
|
||||
if (source>=MIXSRC_RESERVE1 && source<=MIXSRC_RESERVE5)
|
||||
if (source>=MIXSRC_FIRST_RESERVE && source<=MIXSRC_LAST_RESERVE)
|
||||
return false;
|
||||
|
||||
if (source>=MIXSRC_FIRST_TELEM && source<=MIXSRC_LAST_TELEM) {
|
||||
|
|
|
@ -263,7 +263,7 @@ static int luaLcdDrawChannel(lua_State *L)
|
|||
}
|
||||
unsigned int att = luaL_optunsigned(L, 4, 0);
|
||||
getvalue_t value = getValue(channel);
|
||||
putsTelemetryChannelValue(x, y, (channel-MIXSRC_FIRST_TELEM)/3, value, att);
|
||||
drawSensorCustomValue(x, y, (channel-MIXSRC_FIRST_TELEM)/3, value, att);
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
|
|
@ -461,4 +461,8 @@ void perMain()
|
|||
bluetoothWakeup();
|
||||
#endif
|
||||
|
||||
#if INTERNAL_GPS > 0
|
||||
gpsWakeup();
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -340,12 +340,13 @@ void defaultInputs()
|
|||
for (int c=0; c<4; c++) {
|
||||
g_model.inputNames[i][c] = char2idx(STR_INPUTNAMES[1+4*(stick_index-1)+c]);
|
||||
}
|
||||
g_model.inputNames[i][4] = '\0';
|
||||
#else
|
||||
for (int c=0; c<3; c++) {
|
||||
g_model.inputNames[i][c] = char2idx(STR_VSRCRAW[2+4*stick_index+c]);
|
||||
}
|
||||
#if LEN_INPUT_NAME > 3
|
||||
g_model.inputNames[i][3] = '\0';
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
storageDirty(EE_MODEL);
|
||||
|
|
|
@ -1635,7 +1635,7 @@ void varioWakeup();
|
|||
#endif
|
||||
|
||||
#if defined(CPUARM)
|
||||
void putsValueWithUnit(coord_t x, coord_t y, int32_t val, uint8_t unit, LcdFlags att);
|
||||
void drawValueWithUnit(coord_t x, coord_t y, int32_t val, uint8_t unit, LcdFlags att);
|
||||
#elif defined(TELEMETRY_FRSKY)
|
||||
FORCEINLINE void convertUnit(getvalue_t & val, uint8_t & unit)
|
||||
{
|
||||
|
@ -1742,4 +1742,8 @@ extern JitterMeter<uint16_t> avgJitter[NUMBER_ANALOG];
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(INTERNAL_GPS)
|
||||
#include "gps.h"
|
||||
#endif
|
||||
|
||||
#endif // _OPENTX_H_
|
||||
|
|
|
@ -44,6 +44,7 @@ set(GUI_SRC
|
|||
${LAYOUTS_SRC}
|
||||
${WIDGETS_SRC}
|
||||
)
|
||||
set(SRC ${SRC} gps.cpp)
|
||||
if(HELI)
|
||||
set(GUI_SRC ${GUI_SRC} model_heli.cpp)
|
||||
endif()
|
||||
|
|
|
@ -391,7 +391,13 @@ void hapticOff(void);
|
|||
void hapticOn(uint32_t pwmPercent);
|
||||
|
||||
// GPS driver
|
||||
#if PCBREV >= 13
|
||||
#define INTERNAL_GPS 1
|
||||
#else
|
||||
#define INTERNAL_GPS 0
|
||||
#endif
|
||||
void gpsInit(void);
|
||||
uint8_t gpsGetByte(uint8_t * byte);
|
||||
|
||||
// Second serial port driver
|
||||
#define DEBUG_BAUDRATE 115200
|
||||
|
|
|
@ -20,6 +20,8 @@
|
|||
|
||||
#include "opentx.h"
|
||||
|
||||
Fifo<uint8_t, 64> gpsRxFifo;
|
||||
|
||||
void gpsInit()
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
|
@ -76,8 +78,13 @@ extern "C" void GPS_USART_IRQHandler(void)
|
|||
while (status & (USART_FLAG_RXNE | USART_FLAG_ERRORS)) {
|
||||
uint8_t data = GPS_USART->DR;
|
||||
if (!(status & USART_FLAG_ERRORS)) {
|
||||
// TODO gpsRxFifo.push(data);
|
||||
gpsRxFifo.push(data);
|
||||
}
|
||||
status = GPS_USART->SR;
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t gpsGetByte(uint8_t * byte)
|
||||
{
|
||||
return gpsRxFifo.pop(*byte);
|
||||
}
|
|
@ -21,6 +21,8 @@
|
|||
#ifndef _TELEMETRY_SENSORS_H_
|
||||
#define _TELEMETRY_SENSORS_H_
|
||||
|
||||
#include "telemetry.h"
|
||||
|
||||
class TelemetryItem
|
||||
{
|
||||
public:
|
||||
|
|
|
@ -64,7 +64,9 @@ const pm_char STR_OPEN9X[] PROGMEM =
|
|||
ISTR(VFSWFUNC)
|
||||
ISTR(VFSWRESET)
|
||||
ISTR(FUNCSOUNDS)
|
||||
#if !defined(CPUARM)
|
||||
ISTR(VTELEMCHNS)
|
||||
#endif
|
||||
#if defined(TELEMETRY_FRSKY) || defined(CPUARM)
|
||||
ISTR(VTELEMUNIT)
|
||||
ISTR(VALARM)
|
||||
|
|
|
@ -143,7 +143,7 @@ extern const pm_char STR_OPEN9X[];
|
|||
#define OFS_VTELEMCHNS (OFS_FUNCSOUNDS + sizeof(TR_FUNCSOUNDS))
|
||||
#if defined(TELEMETRY_FRSKY) || defined(CPUARM)
|
||||
#if defined(CPUARM)
|
||||
#define OFS_VTELEMUNIT (OFS_VTELEMCHNS + sizeof(TR_VTELEMCHNS))
|
||||
#define OFS_VTELEMUNIT (OFS_VTELEMCHNS)
|
||||
#define OFS_VALARM (OFS_VTELEMUNIT + sizeof(TR_VTELEMUNIT))
|
||||
#else
|
||||
#define OFS_VTELEMUNIT (OFS_VTELEMCHNS + sizeof(TR_VTELEMCHNS))
|
||||
|
|
|
@ -384,42 +384,6 @@
|
|||
|
||||
#define LEN_VTELEMCHNS TR("\004", "\005")
|
||||
|
||||
#if defined(CPUARM)
|
||||
#define TR_TELEM_RESERVE TR("[--]", "[---]")
|
||||
#define TR_TELEM_TIME TR("Time", "Time\0")
|
||||
#define TR_SWR TR("SWR\0", "SWR\0 ")
|
||||
#define TR_RX_BATT TR("[NA]", "[NA]\0")
|
||||
#define TR_A3_A4 TR("A3\0 ""A4\0 ", "A3\0 ""A4\0 ")
|
||||
#define TR_A3_A4_MIN TR("A3-\0""A4-\0", "A3-\0 ""A4-\0 ")
|
||||
#else
|
||||
#define TR_TELEM_RESERVE
|
||||
#define TR_TELEM_TIME
|
||||
#define TR_SWR
|
||||
#define TR_RX_BATT
|
||||
#define TR_A3_A4
|
||||
#define TR_A3_A4_MIN
|
||||
#endif
|
||||
|
||||
#define TR_ASPD_MAX TR("ASp+", "ASpd+")
|
||||
|
||||
#if LCD_W >= 212
|
||||
#define TR_TELEM_RSSI_RX "RSSI\0"
|
||||
#else
|
||||
#define TR_TELEM_RSSI_RX TR("Rx\0 ", "Rx\0 ")
|
||||
#endif
|
||||
|
||||
#if defined(CPUARM)
|
||||
#define TR_TELEM_TIMERS TR("Tmr1""Tmr2""Tmr3", "Tmr1\0""Tmr2\0""Tmr3\0")
|
||||
#else
|
||||
#define TR_TELEM_TIMERS TR("Tmr1""Tmr2", "Tmr1\0""Tmr2\0")
|
||||
#endif
|
||||
|
||||
#if LCD_W >= 212
|
||||
#define TR_VTELEMCHNS "---\0 ""Batt\0" TR_TELEM_TIME TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_TIMERS TR_SWR "Tx\0 " TR_TELEM_RSSI_RX TR_RX_BATT "A1\0 ""A2\0 " TR_A3_A4 "Alt\0 ""Rpm\0 ""Fuel\0""T1\0 ""T2\0 ""Spd\0 ""Dist\0""GAlt\0""Cell\0""Cells""Vfas\0""Curr\0""Cnsp\0""Powr\0""AccX\0""AccY\0""AccZ\0""Hdg\0 ""VSpd\0""ASpd\0""dTE\0 " TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE "A1-\0 ""A2-\0 " TR_A3_A4_MIN "Alt-\0""Alt+\0""Rpm+\0""T1+\0 ""T2+\0 ""Spd+\0""Dst+\0" TR_ASPD_MAX "Cell-""Cels-""Vfas-""Curr+""Powr+" TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE "Acc\0 ""Time\0"
|
||||
#else
|
||||
#define TR_VTELEMCHNS "---\0""Batt" TR_TELEM_TIME TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_TIMERS TR_SWR "Tx\0 " TR_TELEM_RSSI_RX TR_RX_BATT "A1\0 ""A2\0 " TR_A3_A4 "Alt\0""Rpm\0""Fuel""T1\0 ""T2\0 ""Spd\0""Dist""GAlt""Cell""Cels""Vfas""Curr""Cnsp""Powr""AccX""AccY""AccZ""Hdg\0""VSpd""ASpd""dTE\0" TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE "A1-\0""A2-\0" TR_A3_A4_MIN "Alt-""Alt+""Rpm+""T1+\0""T2+\0""Spd+""Dst+" TR_ASPD_MAX "Cel-""Cls-""Vfs-""Cur+""Pwr+" TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE "Acc\0""Time"
|
||||
#endif
|
||||
|
||||
#define LENGTH_UNIT_IMP "ft\0"
|
||||
#define SPEED_UNIT_IMP "mph"
|
||||
#define LENGTH_UNIT_METR "m\0 "
|
||||
|
@ -590,9 +554,10 @@
|
|||
|
||||
#if defined(CPUARM)
|
||||
#define TR_RESERVE_VSRCRAW "[--]"
|
||||
#define TR_EXTRA_VSRCRAW "Batt""Time" TR_RESERVE_VSRCRAW TR_RESERVE_VSRCRAW TR_RESERVE_VSRCRAW TR_RESERVE_VSRCRAW TR_RESERVE_VSRCRAW "Tmr1""Tmr2""Tmr3"
|
||||
#define TR_EXTRA_VSRCRAW "Batt""Time""GPS\0" TR_RESERVE_VSRCRAW TR_RESERVE_VSRCRAW TR_RESERVE_VSRCRAW TR_RESERVE_VSRCRAW "Tmr1""Tmr2""Tmr3"
|
||||
#else
|
||||
#define TR_EXTRA_VSRCRAW
|
||||
#define TR_VTELEMCHNS "---\0" "Batt" "Tmr1""Tmr2""Tx\0 ""Rx\0 ""A1\0 ""A2\0 ""Alt\0""Rpm\0""Fuel""T1\0 ""T2\0 ""Spd\0""Dist""GAlt""Cell""Cels""Vfas""Curr""Cnsp""Powr""AccX""AccY""AccZ""Hdg\0""VSpd""ASpd""dTE\0""A1-\0""A2-\0""Alt-""Alt+""Rpm+""T1+\0""T2+\0""Spd+""Dst+""ASp+""Cel-""Cls-""Vfs-""Cur+""Pwr+""Acc\0""Time"
|
||||
#endif
|
||||
|
||||
#define TR_VSRCRAW "---\0" TR_STICKS_VSRCRAW TR_POTS_VSRCRAW TR_ROTARY_ENCODERS "MAX\0" TR_CYC_VSRCRAW TR_TRIMS_VSRCRAW TR_SW_VSRCRAW TR_EXTRA_VSRCRAW
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue