1
0
Fork 0
mirror of https://github.com/opentx/opentx.git synced 2025-07-25 09:15:38 +03:00

Volts source can be RxBatt/A3/A4 and Amps source A3/A4

This commit is contained in:
bsongis 2014-05-24 16:04:14 +02:00
parent 8f9391a8df
commit c7c58b1a1d
23 changed files with 176 additions and 57 deletions

View file

@ -339,7 +339,7 @@ int ConvertTelemetrySource_215_to_216(int source)
if (source >= TELEM_RSSI_TX) if (source >= TELEM_RSSI_TX)
source += 1; source += 1;
// RxBatt added // RxBatt added
if (source >= TELEM_RX_VOLTAGE) if (source >= TELEM_RXBATT)
source += 1; source += 1;
// A3 and A4 added // A3 and A4 added
if (source >= TELEM_A3) if (source >= TELEM_A3)

View file

@ -5522,14 +5522,14 @@ void menuModelTelemetry(uint8_t event)
#if defined(CPUARM) #if defined(CPUARM)
case ITEM_TELEMETRY_RXBATT_LABEL: case ITEM_TELEMETRY_RXBATT_LABEL:
lcd_putsLeft(y, "RxBatt"); lcd_putsLeft(y, "RxBatt");
putsTelemetryChannel(TELEM_COL2+6*FW, y, TELEM_RX_VOLTAGE-1, frskyData.analog[TELEM_ANA_RxBatt].value, LEFT); putsTelemetryChannel(TELEM_COL2+6*FW, y, TELEM_RXBATT-1, frskyData.analog[TELEM_ANA_RXBATT].value, LEFT);
break; break;
case ITEM_TELEMETRY_RXBATT_ALARM1: case ITEM_TELEMETRY_RXBATT_ALARM1:
case ITEM_TELEMETRY_RXBATT_ALARM2: case ITEM_TELEMETRY_RXBATT_ALARM2:
{ {
uint8_t alarm = (k==ITEM_TELEMETRY_RXBATT_ALARM1 ? 0 : 1); uint8_t alarm = (k==ITEM_TELEMETRY_RXBATT_ALARM1 ? 0 : 1);
lcd_putsLeft(y, (alarm==0 ? STR_LOWALARM : STR_CRITICALALARM)); lcd_putsLeft(y, (alarm==0 ? STR_LOWALARM : STR_CRITICALALARM));
putsTelemetryChannel(TELEM_COL2, y, TELEM_RX_VOLTAGE-1, g_model.rxBattAlarms[alarm], LEFT|attr); putsTelemetryChannel(TELEM_COL2, y, TELEM_RXBATT-1, g_model.rxBattAlarms[alarm], LEFT|attr);
if (attr && (s_editMode>0 || p1valdiff)) { if (attr && (s_editMode>0 || p1valdiff)) {
g_model.rxBattAlarms[alarm] = checkIncDec(event, g_model.rxBattAlarms[alarm], 0, 255, EE_MODEL); g_model.rxBattAlarms[alarm] = checkIncDec(event, g_model.rxBattAlarms[alarm], 0, 255, EE_MODEL);
} }
@ -5699,14 +5699,18 @@ void menuModelTelemetry(uint8_t event)
case ITEM_TELEMETRY_USR_VOLTAGE_SOURCE: case ITEM_TELEMETRY_USR_VOLTAGE_SOURCE:
lcd_putsLeft(y, STR_VOLTAGE); lcd_putsLeft(y, STR_VOLTAGE);
#if defined(CPUARM)
lcd_putsiAtt(TELEM_COL2, y, STR_VOLTSRC, g_model.frsky.voltsSource, attr);
#else
lcd_putsiAtt(TELEM_COL2, y, STR_AMPSRC, g_model.frsky.voltsSource+1, attr); lcd_putsiAtt(TELEM_COL2, y, STR_AMPSRC, g_model.frsky.voltsSource+1, attr);
if (attr) CHECK_INCDEC_MODELVAR_ZERO(event, g_model.frsky.voltsSource, 3); #endif
if (attr) CHECK_INCDEC_MODELVAR_ZERO(event, g_model.frsky.voltsSource, FRSKY_VOLTS_SOURCE_LAST);
break; break;
case ITEM_TELEMETRY_USR_CURRENT_SOURCE: case ITEM_TELEMETRY_USR_CURRENT_SOURCE:
lcd_putsLeft(y, STR_CURRENT); lcd_putsLeft(y, STR_CURRENT);
lcd_putsiAtt(TELEM_COL2, y, STR_AMPSRC, g_model.frsky.currentSource, attr); lcd_putsiAtt(TELEM_COL2, y, STR_AMPSRC, g_model.frsky.currentSource, attr);
if (attr) CHECK_INCDEC_MODELVAR_ZERO(event, g_model.frsky.currentSource, 3); if (attr) CHECK_INCDEC_MODELVAR_ZERO(event, g_model.frsky.currentSource, FRSKY_CURRENT_SOURCE_LAST);
break; break;
#if defined(FAS_OFFSET) || !defined(CPUM64) #if defined(FAS_OFFSET) || !defined(CPUM64)

View file

@ -252,15 +252,19 @@ void displayTopBar()
/* Rx voltage */ /* Rx voltage */
lcdint_t voltage = 0; lcdint_t voltage = 0;
uint8_t channel = 0; uint8_t channel = 0;
if (g_model.frsky.voltsSource <= 1) { if (g_model.frsky.voltsSource == FRSKY_VOLTS_SOURCE_RXBATT) {
channel = TELEM_RXBATT-1;
voltage = frskyData.analog[TELEM_ANA_RXBATT].value;
}
else if (g_model.frsky.voltsSource <= FRSKY_VOLTS_SOURCE_A4) {
channel = TELEM_A1+g_model.frsky.voltsSource-1; channel = TELEM_A1+g_model.frsky.voltsSource-1;
voltage = frskyData.analog[g_model.frsky.voltsSource].value; voltage = frskyData.analog[g_model.frsky.voltsSource].value;
} }
else if (g_model.frsky.voltsSource == 2) { else if (g_model.frsky.voltsSource == FRSKY_VOLTS_SOURCE_FAS) {
channel = TELEM_VFAS-1; channel = TELEM_VFAS-1;
voltage = frskyData.hub.vfas; voltage = frskyData.hub.vfas;
} }
else if (g_model.frsky.voltsSource == 3) { else if (g_model.frsky.voltsSource == FRSKY_VOLTS_SOURCE_CELLS) {
channel = TELEM_CELLS_SUM-1; channel = TELEM_CELLS_SUM-1;
voltage = frskyData.hub.cellsSum; voltage = frskyData.hub.cellsSum;
} }

View file

@ -331,18 +331,27 @@ void menuTelemetryFrsky(uint8_t event)
else if (s_frsky_view == e_frsky_voltages) { else if (s_frsky_view == e_frsky_voltages) {
// Volts / Amps / Watts / mAh // Volts / Amps / Watts / mAh
uint8_t analog = 0; uint8_t analog = 0;
lcd_putsiAtt(0, 2*FH, STR_AMPSRC, g_model.frsky.voltsSource+1, 0); lcd_putsiAtt(0, 2*FH, STR_VOLTSRC, g_model.frsky.voltsSource+1, 0);
switch(g_model.frsky.voltsSource) { switch (g_model.frsky.voltsSource) {
case 0: #if defined(CPUARM)
case 1: case FRSKY_VOLTS_SOURCE_RXBATT:
putsTelemetryChannel(3*FW+6*FW+4, FH+1, TELEM_RXBATT-1, frskyData.analog[TELEM_ANA_RXBATT].value, DBLSIZE);
break;
#endif
case FRSKY_VOLTS_SOURCE_A1:
case FRSKY_VOLTS_SOURCE_A2:
#if defined(CPUARM)
case FRSKY_VOLTS_SOURCE_A3:
case FRSKY_VOLTS_SOURCE_A4:
#endif
displayVoltageScreenLine(2*FH, g_model.frsky.voltsSource); displayVoltageScreenLine(2*FH, g_model.frsky.voltsSource);
analog = 1+g_model.frsky.voltsSource; analog = 1+g_model.frsky.voltsSource;
break; break;
#if defined(FRSKY_HUB) #if defined(FRSKY_HUB)
case 2: case FRSKY_VOLTS_SOURCE_FAS:
putsTelemetryChannel(3*FW+6*FW+4, FH+1, TELEM_VFAS-1, frskyData.hub.vfas, DBLSIZE); putsTelemetryChannel(3*FW+6*FW+4, FH+1, TELEM_VFAS-1, frskyData.hub.vfas, DBLSIZE);
break; break;
case 3: case FRSKY_VOLTS_SOURCE_CELLS:
putsTelemetryChannel(3*FW+6*FW+4, FH+1, TELEM_CELLS_SUM-1, frskyData.hub.cellsSum, DBLSIZE); putsTelemetryChannel(3*FW+6*FW+4, FH+1, TELEM_CELLS_SUM-1, frskyData.hub.cellsSum, DBLSIZE);
break; break;
#endif #endif
@ -351,12 +360,16 @@ void menuTelemetryFrsky(uint8_t event)
if (g_model.frsky.currentSource) { if (g_model.frsky.currentSource) {
lcd_putsiAtt(0, 4*FH, STR_AMPSRC, g_model.frsky.currentSource, 0); lcd_putsiAtt(0, 4*FH, STR_AMPSRC, g_model.frsky.currentSource, 0);
switch(g_model.frsky.currentSource) { switch(g_model.frsky.currentSource) {
case 1: case FRSKY_CURRENT_SOURCE_A1:
case 2: case FRSKY_CURRENT_SOURCE_A2:
#if defined(CPUARM)
case FRSKY_CURRENT_SOURCE_A3:
case FRSKY_CURRENT_SOURCE_A4:
#endif
displayVoltageScreenLine(4*FH, g_model.frsky.currentSource-1); displayVoltageScreenLine(4*FH, g_model.frsky.currentSource-1);
break; break;
#if defined(FRSKY_HUB) #if defined(FRSKY_HUB)
case 3: case FRSKY_CURRENT_SOURCE_FAS:
putsTelemetryChannel(3*FW+6*FW+4, 3*FH+1, TELEM_CURRENT-1, frskyData.hub.current, DBLSIZE); putsTelemetryChannel(3*FW+6*FW+4, 3*FH+1, TELEM_CURRENT-1, frskyData.hub.current, DBLSIZE);
break; break;
#endif #endif

View file

@ -1216,7 +1216,7 @@ void putsTelemetryChannel(xcoord_t x, uint8_t y, uint8_t channel, lcdint_t val,
putsTimer(x, y, val, att, att); putsTimer(x, y, val, att, att);
break; break;
#if defined(CPUARM) #if defined(CPUARM)
case TELEM_RX_VOLTAGE-1: case TELEM_RXBATT-1:
val *= 5; val *= 5;
#if LCD_W >= 212 #if LCD_W >= 212
att |= PREC2; att |= PREC2;

View file

@ -330,7 +330,7 @@ getvalue_t getValue(uint8_t i)
#if defined(FRSKY) #if defined(FRSKY)
#if defined(CPUARM) #if defined(CPUARM)
else if (i==MIXSRC_FIRST_TELEM-1+TELEM_SWR) return frskyData.swr.value; else if (i==MIXSRC_FIRST_TELEM-1+TELEM_SWR) return frskyData.swr.value;
else if (i==MIXSRC_FIRST_TELEM-1+TELEM_RX_VOLTAGE) return frskyData.analog[TELEM_ANA_RxBatt].value; else if (i==MIXSRC_FIRST_TELEM-1+TELEM_RXBATT) return frskyData.analog[TELEM_ANA_RXBATT].value;
#endif #endif
else if (i==MIXSRC_FIRST_TELEM-1+TELEM_RSSI_TX) return frskyData.rssi[1].value; else if (i==MIXSRC_FIRST_TELEM-1+TELEM_RSSI_TX) return frskyData.rssi[1].value;
else if (i==MIXSRC_FIRST_TELEM-1+TELEM_RSSI_RX) return frskyData.rssi[0].value; else if (i==MIXSRC_FIRST_TELEM-1+TELEM_RSSI_RX) return frskyData.rssi[0].value;

View file

@ -1025,7 +1025,7 @@ enum TelemetrySource {
TELEM_RSSI_TX, TELEM_RSSI_TX,
TELEM_RSSI_RX, TELEM_RSSI_RX,
#if defined(CPUARM) #if defined(CPUARM)
TELEM_RX_VOLTAGE, TELEM_RXBATT,
#endif #endif
TELEM_A_FIRST, TELEM_A_FIRST,
TELEM_A1=TELEM_A_FIRST, TELEM_A1=TELEM_A_FIRST,
@ -1166,20 +1166,34 @@ enum FrskyCurrentSource {
FRSKY_CURRENT_SOURCE_NONE, FRSKY_CURRENT_SOURCE_NONE,
FRSKY_CURRENT_SOURCE_A1, FRSKY_CURRENT_SOURCE_A1,
FRSKY_CURRENT_SOURCE_A2, FRSKY_CURRENT_SOURCE_A2,
#if defined(CPUARM)
FRSKY_CURRENT_SOURCE_A3,
FRSKY_CURRENT_SOURCE_A4,
#endif
FRSKY_CURRENT_SOURCE_FAS, FRSKY_CURRENT_SOURCE_FAS,
FRSKY_CURRENT_SOURCE_LAST=FRSKY_CURRENT_SOURCE_FAS
}; };
enum FrskyVoltsSource { enum FrskyVoltsSource {
#if defined(CPUARM)
FRSKY_VOLTS_SOURCE_RXBATT,
#endif
FRSKY_VOLTS_SOURCE_A1, FRSKY_VOLTS_SOURCE_A1,
FRSKY_VOLTS_SOURCE_A2, FRSKY_VOLTS_SOURCE_A2,
#if defined(CPUARM)
FRSKY_VOLTS_SOURCE_A3,
FRSKY_VOLTS_SOURCE_A4,
#endif
FRSKY_VOLTS_SOURCE_FAS, FRSKY_VOLTS_SOURCE_FAS,
FRSKY_VOLTS_SOURCE_CELLS, FRSKY_VOLTS_SOURCE_CELLS,
FRSKY_VOLTS_SOURCE_LAST=FRSKY_VOLTS_SOURCE_CELLS
}; };
#if defined(CPUARM) #if defined(CPUARM)
#define MAX_FRSKY_A_CHANNELS 4
#define MAX_FRSKY_SCREENS 3 #define MAX_FRSKY_SCREENS 3
PACK(typedef struct t_FrSkyData { PACK(typedef struct t_FrSkyData {
FrSkyChannelData channels[4]; FrSkyChannelData channels[MAX_FRSKY_A_CHANNELS];
uint8_t usrProto; // Protocol in FrSky user data, 0=None, 1=FrSky hub, 2=WS HowHigh, 3=Halcyon uint8_t usrProto; // Protocol in FrSky user data, 0=None, 1=FrSky hub, 2=WS HowHigh, 3=Halcyon
uint8_t voltsSource:7; uint8_t voltsSource:7;
uint8_t altitudeDisplayed:1; uint8_t altitudeDisplayed:1;
@ -1200,9 +1214,10 @@ PACK(typedef struct t_FrSkyData {
#define MIN_BLADES -1 // 1 blade #define MIN_BLADES -1 // 1 blade
#define MAX_BLADES 126 // 128 blades #define MAX_BLADES 126 // 128 blades
#else #else
#define MAX_FRSKY_A_CHANNELS 2
#define MAX_FRSKY_SCREENS 2 #define MAX_FRSKY_SCREENS 2
PACK(typedef struct t_FrSkyData { PACK(typedef struct t_FrSkyData {
FrSkyChannelData channels[2]; FrSkyChannelData channels[MAX_FRSKY_A_CHANNELS];
uint8_t usrProto:2; // Protocol in FrSky user data, 0=None, 1=FrSky hub, 2=WS HowHigh, 3=Halcyon uint8_t usrProto:2; // Protocol in FrSky user data, 0=None, 1=FrSky hub, 2=WS HowHigh, 3=Halcyon
uint8_t blades:2; // How many blades for RPMs, 0=2 blades uint8_t blades:2; // How many blades for RPMs, 0=2 blades
uint8_t screensType:2; uint8_t screensType:2;

View file

@ -1608,7 +1608,7 @@ PLAY_FUNCTION(playValue, uint8_t idx)
case MIXSRC_FIRST_TELEM+TELEM_SWR-1: case MIXSRC_FIRST_TELEM+TELEM_SWR-1:
PLAY_NUMBER(val, 0, 0); PLAY_NUMBER(val, 0, 0);
break; break;
case MIXSRC_FIRST_TELEM+TELEM_RX_VOLTAGE-1: case MIXSRC_FIRST_TELEM+TELEM_RXBATT-1:
if (TELEMETRY_STREAMING()) { if (TELEMETRY_STREAMING()) {
PLAY_NUMBER(val/2, 1+UNIT_VOLTS, PREC1); PLAY_NUMBER(val/2, 1+UNIT_VOLTS, PREC1);
} }

View file

@ -129,7 +129,7 @@ void FrskyValueWithMinMax::set(uint8_t value, uint8_t unit)
#if defined(CPUARM) #if defined(CPUARM)
inline bool rxBattAlarmRaised(uint8_t alarm) inline bool rxBattAlarmRaised(uint8_t alarm)
{ {
return g_model.rxBattAlarms[alarm] > 0 && frskyData.analog[TELEM_ANA_RxBatt].value < g_model.rxBattAlarms[alarm]; return g_model.rxBattAlarms[alarm] > 0 && frskyData.analog[TELEM_ANA_RXBATT].value < g_model.rxBattAlarms[alarm];
} }
inline bool alarmRaised(uint8_t channel, uint8_t idx) inline bool alarmRaised(uint8_t channel, uint8_t idx)
{ {
@ -433,11 +433,21 @@ void telemetryInterrupt10ms()
if (!TELEMETRY_OPENXSENSOR()) { if (!TELEMETRY_OPENXSENSOR()) {
// power calculation // power calculation
uint8_t channel = g_model.frsky.voltsSource; uint8_t channel = g_model.frsky.voltsSource;
if (channel <= 1) { #if defined(CPUARM)
if (channel == FRSKY_VOLTS_SOURCE_RXBATT) {
voltage = frskyData.analog[TELEM_ANA_RXBATT].value / 2;
}
else if (channel <= FRSKY_VOLTS_SOURCE_A4) {
voltage = applyChannelRatio(channel, frskyData.analog[channel].value) / 10; voltage = applyChannelRatio(channel, frskyData.analog[channel].value) / 10;
} }
#else
if (channel <= FRSKY_VOLTS_SOURCE_A2) {
voltage = applyChannelRatio(channel, frskyData.analog[channel].value) / 10;
}
#endif
#if defined(FRSKY_HUB) #if defined(FRSKY_HUB)
else if (channel == 2) { else if (channel == FRSKY_VOLTS_SOURCE_FAS) {
voltage = frskyData.hub.vfas; voltage = frskyData.hub.vfas;
} }
#endif #endif
@ -449,7 +459,7 @@ void telemetryInterrupt10ms()
#endif #endif
channel = g_model.frsky.currentSource - FRSKY_CURRENT_SOURCE_A1; channel = g_model.frsky.currentSource - FRSKY_CURRENT_SOURCE_A1;
if (channel <= 1) { if (channel <= MAX_FRSKY_A_CHANNELS) {
current = applyChannelRatio(channel, frskyData.analog[channel].value) / 10; current = applyChannelRatio(channel, frskyData.analog[channel].value) / 10;
} }

View file

@ -287,7 +287,7 @@ enum TelemAnas {
#if defined(CPUARM) #if defined(CPUARM)
TELEM_ANA_A3, TELEM_ANA_A3,
TELEM_ANA_A4, TELEM_ANA_A4,
TELEM_ANA_RxBatt, TELEM_ANA_RXBATT,
#endif #endif
TELEM_ANA_COUNT TELEM_ANA_COUNT
}; };

View file

@ -321,7 +321,7 @@ void frskySportProcessPacket(uint8_t *packet)
#endif #endif
} }
else if (appId == BATT_ID) { else if (appId == BATT_ID) {
frskyData.analog[TELEM_ANA_RxBatt].set((SPORT_DATA_U32(packet)*132/255)/5, UNIT_VOLTS); frskyData.analog[TELEM_ANA_RXBATT].set((SPORT_DATA_U32(packet)*132/255)/5, UNIT_VOLTS);
} }
else if ((appId >> 8) == 0) { else if ((appId >> 8) == 0) {
// The old FrSky IDs // The old FrSky IDs

View file

@ -84,7 +84,7 @@ const pm_char STR_OPEN9X[] PROGMEM =
ISTR(VALARMFN) ISTR(VALARMFN)
ISTR(VTELPROTO) ISTR(VTELPROTO)
ISTR(GPSFORMAT) ISTR(GPSFORMAT)
ISTR(VOLTSRC) ISTR(AMPSRC)
ISTR(VARIOSRC) ISTR(VARIOSRC)
ISTR(VSCREEN) ISTR(VSCREEN)
#endif #endif
@ -115,6 +115,7 @@ const pm_char STR_OPEN9X[] PROGMEM =
ISTR(TARANIS_PROTOCOLS) ISTR(TARANIS_PROTOCOLS)
ISTR(XJT_PROTOCOLS) ISTR(XJT_PROTOCOLS)
ISTR(DSM_PROTOCOLS) ISTR(DSM_PROTOCOLS)
ISTR(VOLTSRC)
ISTR(CURVE_TYPES) ISTR(CURVE_TYPES)
#endif #endif
#if defined(MAVLINK) #if defined(MAVLINK)

View file

@ -134,7 +134,7 @@ extern const pm_char STR_OPEN9X[];
#define OFS_VALARMFN (OFS_VALARM + sizeof(TR_VALARM)) #define OFS_VALARMFN (OFS_VALARM + sizeof(TR_VALARM))
#define OFS_VTELPROTO (OFS_VALARMFN + sizeof(TR_VALARMFN)) #define OFS_VTELPROTO (OFS_VALARMFN + sizeof(TR_VALARMFN))
#define OFS_GPSFORMAT (OFS_VTELPROTO + sizeof(TR_VTELPROTO)) #define OFS_GPSFORMAT (OFS_VTELPROTO + sizeof(TR_VTELPROTO))
#define OFS_AMPSRC (OFS_GPSFORMAT + sizeof(TR_GPSFORMAT)) #define OFS_AMPSRC (OFS_GPSFORMAT + sizeof(TR_GPSFORMAT))
#define OFS_VARIOSRC (OFS_AMPSRC + sizeof(TR_AMPSRC)) #define OFS_VARIOSRC (OFS_AMPSRC + sizeof(TR_AMPSRC))
#define OFS_VSCREEN (OFS_VARIOSRC + sizeof(TR_VARIOSRC)) #define OFS_VSCREEN (OFS_VARIOSRC + sizeof(TR_VARIOSRC))
#define OFS_VTEMPLATES (OFS_VSCREEN + sizeof(TR_VSCREEN)) #define OFS_VTEMPLATES (OFS_VSCREEN + sizeof(TR_VSCREEN))
@ -178,7 +178,8 @@ extern const pm_char STR_OPEN9X[];
#define OFS_TARANIS_PROTOCOLS (OFS_VTRAINERMODES + sizeof(TR_VTRAINERMODES)) #define OFS_TARANIS_PROTOCOLS (OFS_VTRAINERMODES + sizeof(TR_VTRAINERMODES))
#define OFS_XJT_PROTOCOLS (OFS_TARANIS_PROTOCOLS + sizeof(TR_TARANIS_PROTOCOLS)) #define OFS_XJT_PROTOCOLS (OFS_TARANIS_PROTOCOLS + sizeof(TR_TARANIS_PROTOCOLS))
#define OFS_DSM_PROTOCOLS (OFS_XJT_PROTOCOLS + sizeof(TR_XJT_PROTOCOLS)) #define OFS_DSM_PROTOCOLS (OFS_XJT_PROTOCOLS + sizeof(TR_XJT_PROTOCOLS))
#define OFS_CURVE_TYPES (OFS_DSM_PROTOCOLS + sizeof(TR_DSM_PROTOCOLS)) #define OFS_VOLTSRC (OFS_DSM_PROTOCOLS + sizeof(TR_DSM_PROTOCOLS))
#define OFS_CURVE_TYPES (OFS_VOLTSRC + sizeof(TR_VOLTSRC))
#define OFS_MAVLINK_BAUDS (OFS_CURVE_TYPES + sizeof(TR_CURVE_TYPES)) #define OFS_MAVLINK_BAUDS (OFS_CURVE_TYPES + sizeof(TR_CURVE_TYPES))
#else #else
#define OFS_MAVLINK_BAUDS (OFS_VTRAINERMODES) #define OFS_MAVLINK_BAUDS (OFS_VTRAINERMODES)
@ -222,6 +223,7 @@ extern const pm_char STR_OPEN9X[];
#if defined(FRSKY) || defined(CPUARM) #if defined(FRSKY) || defined(CPUARM)
#if defined(CPUARM) #if defined(CPUARM)
#define STR_VTELEMUNIT (STR_OPEN9X + (g_eeGeneral.imperial ? OFS_VTELEMUNIT_IMP : OFS_VTELEMUNIT_METR)) #define STR_VTELEMUNIT (STR_OPEN9X + (g_eeGeneral.imperial ? OFS_VTELEMUNIT_IMP : OFS_VTELEMUNIT_METR))
#define STR_VOLTSRC (STR_OPEN9X + OFS_VOLTSRC)
#else #else
#define STR_VTELEMUNIT (STR_OPEN9X + OFS_VTELEMUNIT) #define STR_VTELEMUNIT (STR_OPEN9X + OFS_VTELEMUNIT)
#endif #endif
@ -229,18 +231,18 @@ extern const pm_char STR_OPEN9X[];
#define STR_VALARMFN (STR_OPEN9X + OFS_VALARMFN) #define STR_VALARMFN (STR_OPEN9X + OFS_VALARMFN)
#define STR_VTELPROTO (STR_OPEN9X + OFS_VTELPROTO) #define STR_VTELPROTO (STR_OPEN9X + OFS_VTELPROTO)
#define STR_GPSFORMAT (STR_OPEN9X + OFS_GPSFORMAT) #define STR_GPSFORMAT (STR_OPEN9X + OFS_GPSFORMAT)
#define STR_AMPSRC (STR_OPEN9X + OFS_AMPSRC) #define STR_AMPSRC (STR_OPEN9X + OFS_AMPSRC)
#define STR_VARIOSRC (STR_OPEN9X + OFS_VARIOSRC) #define STR_VARIOSRC (STR_OPEN9X + OFS_VARIOSRC)
#define STR_VSCREEN (STR_OPEN9X + OFS_VSCREEN) #define STR_VSCREEN (STR_OPEN9X + OFS_VSCREEN)
#define STR_TELEMCHNS (STR_OPEN9X + OFS_TELEMCHNS) #define STR_TELEMCHNS (STR_OPEN9X + OFS_TELEMCHNS)
#endif #endif
#ifdef TEMPLATES #if defined(TEMPLATES)
#define STR_VTEMPLATES (STR_OPEN9X + OFS_VTEMPLATES) #define STR_VTEMPLATES (STR_OPEN9X + OFS_VTEMPLATES)
#endif #endif
#ifdef HELI #if defined(HELI)
#define STR_VSWASHTYPE (STR_OPEN9X + OFS_VSWASHTYPE) #define STR_VSWASHTYPE (STR_OPEN9X + OFS_VSWASHTYPE)
#endif #endif
#define STR_VKEYS (STR_OPEN9X + OFS_VKEYS) #define STR_VKEYS (STR_OPEN9X + OFS_VKEYS)

View file

@ -354,8 +354,15 @@
#define LEN_VTELPROTO "\007" #define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "---\0 ""Hub\0 ""WSHHigh" #define TR_VTELPROTO "---\0 ""Hub\0 ""WSHHigh"
#define LEN_AMPSRC "\003" #if defined(CPUARM)
#define TR_AMPSRC "---""A1\0""A2\0""FAS""Cel" #define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#define LEN_VOLTSRC TR("\003", "\007")
#define TR_VOLTSRC TR("RxV""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "RxBatt\0""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#else
#define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""FAS\0 ""Cells\0 ")
#endif
#define LEN_VARIOSRC "\005" #define LEN_VARIOSRC "\005"
#if defined(FRSKY_SPORT) #if defined(FRSKY_SPORT)

View file

@ -354,8 +354,15 @@
#define LEN_VTELPROTO "\007" #define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "Kein\0 ""Hub\0 ""WSHHigh" #define TR_VTELPROTO "Kein\0 ""Hub\0 ""WSHHigh"
#define LEN_AMPSRC TR("\003", "\007") #if defined(CPUARM)
#define TR_AMPSRC TR("---""A1\0""A2\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""FAS\0 ""Cells\0 ") #define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#define LEN_VOLTSRC TR("\003", "\007")
#define TR_VOLTSRC TR("RxV""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "RxBatt\0""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#else
#define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""FAS\0 ""Cells\0 ")
#endif
#define LEN_VARIOSRC "\004" #define LEN_VARIOSRC "\004"
#if defined(FRSKY_SPORT) #if defined(FRSKY_SPORT)

View file

@ -354,8 +354,15 @@
#define LEN_VTELPROTO "\007" #define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "None\0 ""Hub\0 ""WSHHigh" #define TR_VTELPROTO "None\0 ""Hub\0 ""WSHHigh"
#define LEN_AMPSRC TR("\003", "\007") #if defined(CPUARM)
#define TR_AMPSRC TR("---""A1\0""A2\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""FAS\0 ""Cells\0 ") #define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#define LEN_VOLTSRC TR("\003", "\007")
#define TR_VOLTSRC TR("RxV""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "RxBatt\0""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#else
#define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""FAS\0 ""Cells\0 ")
#endif
#define LEN_VARIOSRC "\004" #define LEN_VARIOSRC "\004"
#if defined(FRSKY_SPORT) #if defined(FRSKY_SPORT)

View file

@ -354,8 +354,15 @@
#define LEN_VTELPROTO "\007" #define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "Nada\0 ""Hub\0 ""WSHHigh" #define TR_VTELPROTO "Nada\0 ""Hub\0 ""WSHHigh"
#define LEN_AMPSRC "\003" #if defined(CPUARM)
#define TR_AMPSRC "---""A1\0""A2\0""FAS""Cel" #define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#define LEN_VOLTSRC TR("\003", "\007")
#define TR_VOLTSRC TR("RxV""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "RxBatt\0""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#else
#define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""FAS\0 ""Cells\0 ")
#endif
#define LEN_VARIOSRC "\005" #define LEN_VARIOSRC "\005"
#if defined(FRSKY_SPORT) #if defined(FRSKY_SPORT)

View file

@ -354,8 +354,15 @@
#define LEN_VTELPROTO "\007" #define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "None\0 ""Hub\0 ""WSHHigh" #define TR_VTELPROTO "None\0 ""Hub\0 ""WSHHigh"
#define LEN_AMPSRC "\003" #if defined(CPUARM)
#define TR_AMPSRC "---""A1\0""A2\0""FAS""Cel" #define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#define LEN_VOLTSRC TR("\003", "\007")
#define TR_VOLTSRC TR("RxV""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "RxBatt\0""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#else
#define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""FAS\0 ""Cells\0 ")
#endif
#define LEN_VARIOSRC "\005" #define LEN_VARIOSRC "\005"
#if defined(FRSKY_SPORT) #if defined(FRSKY_SPORT)

View file

@ -354,8 +354,15 @@
#define LEN_VTELPROTO "\007" #define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "Aucun ""Hub\0 ""WSHHigh" #define TR_VTELPROTO "Aucun ""Hub\0 ""WSHHigh"
#define LEN_AMPSRC "\003" #if defined(CPUARM)
#define TR_AMPSRC "---""A1\0""A2\0""FAS""Elm" #define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#define LEN_VOLTSRC TR("\003", "\007")
#define TR_VOLTSRC TR("RxV""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "RxBatt\0""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#else
#define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""FAS\0 ""Cells\0 ")
#endif
#define LEN_VARIOSRC "\005" #define LEN_VARIOSRC "\005"
#if defined(FRSKY_SPORT) #if defined(FRSKY_SPORT)

View file

@ -354,8 +354,15 @@
#define LEN_VTELPROTO "\007" #define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "---\0 ""Hub\0 ""WSHHigh" #define TR_VTELPROTO "---\0 ""Hub\0 ""WSHHigh"
#define LEN_AMPSRC "\003" #if defined(CPUARM)
#define TR_AMPSRC "---""A1\0""A2\0""FAS""Cel" #define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#define LEN_VOLTSRC TR("\003", "\007")
#define TR_VOLTSRC TR("RxV""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "RxBatt\0""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#else
#define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""FAS\0 ""Cells\0 ")
#endif
#define LEN_VARIOSRC "\005" #define LEN_VARIOSRC "\005"
#if defined(FRSKY_SPORT) #if defined(FRSKY_SPORT)

View file

@ -354,8 +354,15 @@
#define LEN_VTELPROTO "\007" #define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "None\0 ""Hub\0 ""WSHHigh" #define TR_VTELPROTO "None\0 ""Hub\0 ""WSHHigh"
#define LEN_AMPSRC TR("\003", "\007") #if defined(CPUARM)
#define TR_AMPSRC TR("---""A1\0""A2\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""FAS\0 ""Cells\0 ") #define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#define LEN_VOLTSRC TR("\003", "\007")
#define TR_VOLTSRC TR("RxV""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "RxBatt\0""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#else
#define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""FAS\0 ""Cells\0 ")
#endif
#define LEN_VARIOSRC "\004" #define LEN_VARIOSRC "\004"
#if defined(FRSKY_SPORT) #if defined(FRSKY_SPORT)

View file

@ -354,8 +354,15 @@
#define LEN_VTELPROTO "\007" #define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "Nada\0 ""Hub\0 ""WSHHigh" #define TR_VTELPROTO "Nada\0 ""Hub\0 ""WSHHigh"
#define LEN_AMPSRC "\003" #if defined(CPUARM)
#define TR_AMPSRC "---""A1\0""A2\0""FAS""Cel" #define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#define LEN_VOLTSRC TR("\003", "\007")
#define TR_VOLTSRC TR("RxV""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "RxBatt\0""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#else
#define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""FAS\0 ""Cells\0 ")
#endif
#define LEN_VARIOSRC "\005" #define LEN_VARIOSRC "\005"
#if defined(FRSKY_SPORT) #if defined(FRSKY_SPORT)

View file

@ -354,8 +354,15 @@
#define LEN_VTELPROTO "\007" #define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "---\0 ""Hub\0 ""WSHHög." #define TR_VTELPROTO "---\0 ""Hub\0 ""WSHHög."
#define LEN_AMPSRC "\003" #if defined(CPUARM)
#define TR_AMPSRC "---""A1\0""A2\0""FAS""Cel" #define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#define LEN_VOLTSRC TR("\003", "\007")
#define TR_VOLTSRC TR("RxV""A1\0""A2\0""A3\0""A4\0""FAS""Cel", "RxBatt\0""A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells\0 ")
#else
#define LEN_AMPSRC TR("\003", "\007")
#define TR_AMPSRC TR("---""A1\0""A2\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""FAS\0 ""Cells\0 ")
#endif
#define LEN_VARIOSRC "\005" #define LEN_VARIOSRC "\005"
#if defined(FRSKY_SPORT) #if defined(FRSKY_SPORT)