1
0
Fork 0
mirror of https://github.com/opentx/opentx.git synced 2025-07-20 06:45:10 +03:00

Remove unused telemetry protocols

This commit is contained in:
Arne Schwabe 2018-07-05 10:39:57 +02:00
parent d831b0f55e
commit e76d1d0c3d
32 changed files with 14 additions and 3296 deletions

View file

@ -69,9 +69,6 @@ set(EEPROM_VARIANT 0)
set(GVARS_VARIANT 1)
set(FRSKY_VARIANT 2)
set(3POS_VARIANT 4)
set(MAVLINK_VARIANT 8)
set(M2561_VARIANT 16384)
set(M128_VARIANT 32768)
set(FIRMWARE_DEPENDENCIES firmware_translations)

View file

@ -355,14 +355,6 @@ PACK(struct FrSkyTelemetryData {
* MAVLINK Telemetry structure
*/
#if defined(TELEMETRY_MAVLINK)
PACK(struct MavlinkTelemetryData {
uint8_t rc_rssi_scale:4;
uint8_t pc_rssi_en:1;
uint8_t spare1:3;
uint8_t spare2[3];
});
#endif
/*
* Telemetry Sensor structure

View file

@ -20,9 +20,6 @@
#include "opentx.h"
#if defined(TELEMETRY_MAVLINK)
#include "view_mavlink.h"
#endif
uint8_t editDelay(coord_t y, event_t event, uint8_t attr, const pm_char * str, uint8_t delay)
{

View file

@ -518,11 +518,6 @@ void menuRadioSetup(event_t event)
break;
#endif
#if defined(TELEMETRY_MAVLINK)
case ITEM_MAVLINK_BAUD:
g_eeGeneral.mavbaud = editChoice(RADIO_SETUP_2ND_COLUMN, y, STR_MAVLINK_BAUD_LABEL, STR_MAVLINK_BAUDS, g_eeGeneral.mavbaud, 0, 7, attr, event);
break;
#endif
case ITEM_SETUP_SWITCHES_DELAY:
lcdDrawTextAlignedLeft(y, STR_SWITCHES_DELAY);

View file

@ -398,17 +398,6 @@ void menuMainView(event_t event)
case EVT_KEY_TELEMETRY:
#if defined(TELEMETRY_FRSKY)
chainMenu(menuViewTelemetryFrsky);
#elif defined(TELEMETRY_JETI)
JETI_EnableRXD(); // enable JETI-Telemetry reception
chainMenu(menuViewTelemetryJeti);
#elif defined(TELEMETRY_ARDUPILOT)
ARDUPILOT_EnableRXD(); // enable ArduPilot-Telemetry reception
chainMenu(menuViewTelemetryArduPilot);
#elif defined(TELEMETRY_NMEA)
NMEA_EnableRXD(); // enable NMEA-Telemetry reception
chainMenu(menuViewTelemetryNMEA);
#elif defined(TELEMETRY_MAVLINK)
chainMenu(menuViewTelemetryMavlink);
#else
chainMenu(menuStatisticsDebug);
#endif

View file

@ -466,11 +466,6 @@ void menuRadioSetup(event_t event)
break;
#endif
#if defined(TELEMETRY_MAVLINK)
case ITEM_MAVLINK_BAUD:
g_eeGeneral.mavbaud = editChoice(RADIO_SETUP_2ND_COLUMN, y, STR_MAVLINK_BAUD_LABEL, STR_MAVLINK_BAUDS, g_eeGeneral.mavbaud, 0, 7, attr, event);
break;
#endif
case ITEM_SETUP_SWITCHES_DELAY:
lcdDrawTextAlignedLeft(y, STR_SWITCHES_DELAY);

View file

@ -442,12 +442,6 @@ bool menuRadioSetup(event_t event)
break;
#endif
#if defined(TELEMETRY_MAVLINK)
case ITEM_MAVLINK_BAUD:
lcdDrawText(MENUS_MARGIN_LEFT, y, STR_MAVLINK_BAUD_LABEL);
g_eeGeneral.mavbaud = editChoice(RADIO_SETUP_2ND_COLUMN, y, STR_MAVLINK_BAUDS, g_eeGeneral.mavbaud, 0, 7, attr, event);
break;
#endif
case ITEM_SETUP_SWITCHES_DELAY:
lcdDrawText(MENUS_MARGIN_LEFT, y, STR_SWITCHES_DELAY);

View file

@ -505,10 +505,6 @@ void modelDefault(uint8_t id)
}
#endif
#if defined(TELEMETRY_MAVLINK)
g_model.mavlink.rc_rssi_scale = 15;
g_model.mavlink.pc_rssi_en = 1;
#endif
#if !defined(EEPROM)
strcpy(g_model.header.name, "\015\361\374\373\364");
@ -2225,21 +2221,9 @@ int main()
DSM2_Init();
#endif
#if defined(TELEMETRY_JETI)
JETI_Init();
#endif
#if defined(TELEMETRY_ARDUPILOT)
ARDUPILOT_Init();
#endif
#if defined(TELEMETRY_NMEA)
NMEA_Init();
#endif
#if defined(TELEMETRY_MAVLINK)
MAVLINK_Init();
#endif
#if defined(MENU_ROTARY_SW)
init_rotary_sw();

View file

@ -128,11 +128,7 @@
#define CASE_FRSKY(x)
#endif
#if defined(TELEMETRY_MAVLINK)
#define CASE_MAVLINK(x) x,
#else
#define CASE_MAVLINK(x)
#endif
#if defined(PXX)
#define CASE_PXX(x) x,

View file

@ -1,716 +0,0 @@
/*
* 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"
#define NB_BUF 2
#define LG_BUF 11
#define VALSTR(val) (rbuf[val][0] ? rbuf[val] : val_unknown)
#define APSIZE (BSS | DBLSIZE)
/* Received data
Data are received as packets, each packet is identified by a prefix of three
characters and is ended by three stars. Some packets can contain more than
one value, the values are ended by a comma.
Position packet:
!!!LAT:0123456789,LON:9876543210,SPD:123,CRT:1,ALT:123456,ALH:654321,CRS:123,BER:123,WPN:12,DST:12345,BTV:12.4567 9012,RSP:123,TOW:123456,***
...----1--------------2--------------3-------4-----5----------6----------7-------8-------9------10--------11-----------12----------13-----END
1st value 2nd value
Attitude packet:
+++ASP:123,THH:123,RLL:123,PCH:123,***
...----1-------2-------3-------4---END
Mode change packet:
###STABILIZE***
...1--------END
Waypoint packet:
%%%12 45***
...1----END
Alert packet:
XXXAlert Text alert***
...1---------------END
Performance packet:
PPPThis is performant***
...1--------------END
*/
// Position packet prefix
#define PACK_POS 0x21
// value occurence number in this packet
#define LAT 1
#define LON 2
#define SPD 3
#define CRT 4
#define ALT 5
#define ALH 6
#define CRS 7
#define BER 8
#define WPN 9
#define DST 10
#define BTV 11
#define RSP 12
#define TOW 13
#define PACK_ATT 0x2b
// value occurence number in this packet
#define ASP 1
#define THH 2
#define RLL 3
#define PCH 4
#define PACK_MOD 0x23
// value occurence number in this packet
#define MOD 1
#define PACK_WPC 0x25
// value occurence number in this packet
#define WPC 1
#define PACK_ALR 0x58
// value occurence number in this packet
#define ALR 1
#define PACK_PRF 0x50
// value occurence number in this packet
#define PRF 1
// end of packet
#define PACK_END 0x2a
// end of value
#define VAL_END 0x2c
// end of title
#define TITLE_END 0x3a
// stateful machine
// Since the packets are sent continuously, we need to synchronize on the
// reception of the three chars prefixing a packet, whatever they are.
// states values
#define WAIT_PACKET 1
#define WAIT_PACK_POS1 2
#define WAIT_PACK_POS2 3
#define WAIT_PACK_POS3 4
#define WAIT_PACK_ATT1 5
#define WAIT_PACK_ATT2 6
#define WAIT_PACK_ATT3 7
#define WAIT_PACK_MOD1 8
#define WAIT_PACK_MOD2 9
#define WAIT_PACK_MOD3 10
#define WAIT_PACK_WPC1 11
#define WAIT_PACK_WPC2 12
#define WAIT_PACK_WPC3 13
#define WAIT_PACK_ALR1 14
#define WAIT_PACK_ALR2 15
#define WAIT_PACK_ALR3 16
#define WAIT_PACK_PRF1 17
#define WAIT_PACK_PRF2 18
#define WAIT_PACK_PRF3 19
#define FLUSH_TITLE1 20
#define FLUSH_TITLE2 21
#define FLUSH_TITLE3 22
#define FLUSH_TITLE4 23
#define READ_VALUE 24
uint8_t i; // working variable
uint8_t state; // currrent state
uint8_t rval, rpack; // received items
uint8_t xval[NB_BUF]; // expected value
uint8_t xpack[NB_BUF]; // expected packet
uint8_t ibuf[NB_BUF]; // subscripts on buffers values
char rbuf[NB_BUF][LG_BUF]; // receive buffers
const char val_unknown[] = "?";
void menuViewTelemetryArduPilot1(event_t event);
void menuViewTelemetryArduPilot2(event_t event);
void menuViewTelemetryArduPilot3(event_t event);
void menuViewTelemetryArduPilot4(event_t event);
void menuViewTelemetryArduPilot5(event_t event);
void menuViewTelemetryArduPilot6(event_t event);
void menuViewTelemetryArduPilot7(event_t event);
void menuViewTelemetryArduPilot8(event_t event);
void title(char x);
void initval(uint8_t num, uint8_t pack, uint8_t val);
#ifndef SIMU
ISR (USART0_RX_vect)
{
uint8_t rl;
// uint8_t rh; //USART control and Status Register 0 B
uint8_t iostat; //USART control and Status Register 0 A
rl = UDR0;
iostat = UCSR0A; //USART control and Status Register 0 A
/*
bit 7 6 5 4 3 2 1 0
RxC0 TxC0 UDRE0 FE0 DOR0 UPE0 U2X0 MPCM0
RxC0: Receive complete
TXC0: Transmit Complete
UDRE0: USART Data Register Empty
FE0: Frame Error
DOR0: Data OverRun
UPE0: USART Parity Error
U2X0: Double Tx Speed
MPCM0: MultiProcessor Comms Mode
*/
if (iostat & ((1 << FE0) | (1 << DOR0) | (1 << UPE0)))
{
rl = xpack[0] = xpack[1] = xval[0] = xval[1] = 0;
state = WAIT_PACKET; // restart on error
}
// rh = UCSR0B; //USART control and Status Register 0 B
/* bit 7 6 5 4 3 2 1 0
RxCIE0 TxCIE0 UDRIE0 RXEN0 TXEN0 UCSZ02 RXB80 TXB80
RxCIE0: Receive complete int enable
TXCIE0: Transmit Complete int enable
UDRIE0: USART Data Register Empty int enable
RXEN0: Rx enable
TXEN0: Tx Enable
UCSZ02: Character Size bit 2
RXB80: Rx data bit 8
TXB80: Tx data bit 8
*/
switch (state)
{
case WAIT_PACKET:
switch (rl)
{
case PACK_POS: // found a new POS packet
state = WAIT_PACK_POS2; // wait for the 2nd char
break;
case PACK_ATT: // found a new ATT packet
state = WAIT_PACK_ATT2; // wait for the 2nd char
break;
case PACK_MOD: // found a new MOD packet
state = WAIT_PACK_MOD2; // wait for the 2nd char
break;
case PACK_WPC: // found a new WPC packet
state = WAIT_PACK_WPC2; // wait for the 2nd char
break;
case PACK_ALR: // found a new ALR packet
state = WAIT_PACK_ALR2; // wait for the 2nd char
break;
case PACK_PRF: // found a new PRF packet
state = WAIT_PACK_PRF2; // wait for the 2nd char
break;
}
break;
case WAIT_PACK_POS2: // wait for 2nd char
if (rl == PACK_POS)
state = WAIT_PACK_POS3;
else
state = WAIT_PACKET; // restart if not found
break;
case WAIT_PACK_POS3: // wait for 3rd char
if (rl == PACK_POS) // found
{
state = FLUSH_TITLE1; // flush title "LAT:"
rpack = PACK_POS;
rval = 1;
for (i = 0; i < NB_BUF; i++)
ibuf[i] = 0;
}
else
state = WAIT_PACKET; // restart if not found
break;
case WAIT_PACK_ATT2: // wait for 2nd char
if (rl == PACK_ATT)
state = WAIT_PACK_ATT3;
else
state = WAIT_PACKET; // restart if not found
break;
case WAIT_PACK_ATT3: // wait for 3rd char
if (rl == PACK_ATT)
{
state = FLUSH_TITLE1; // flush title "ASP:"
rpack = PACK_ATT;
rval = 1;
for (i = 0; i < NB_BUF; i++)
ibuf[i] = 0;
}
else
state = WAIT_PACKET; // restart if not found
break;
case WAIT_PACK_MOD2: // wait for 2nd char
if (rl == PACK_MOD)
state = WAIT_PACK_MOD3;
else
state = WAIT_PACKET; // restart if not found
break;
case WAIT_PACK_MOD3: // wait for 3rd char
if (rl == PACK_MOD)
{
state = READ_VALUE; // ready to read values from PACK_MOD packet
rpack = PACK_MOD;
rval = 1;
for (i = 0; i < NB_BUF; i++)
ibuf[i] = 0;
}
else
state = WAIT_PACKET; // restart if not found
break;
case WAIT_PACK_WPC2: // wait for 2nd char
if (rl == PACK_WPC)
state = WAIT_PACK_WPC3;
else
state = WAIT_PACKET; // restart if not found
break;
case WAIT_PACK_WPC3: // wait for 3rd char
if (rl == PACK_WPC)
{
state = READ_VALUE; // ready to read values from PACK_WPC packet
rpack = PACK_WPC;
rval = 1;
for (i = 0; i < NB_BUF; i++)
ibuf[i] = 0;
}
else
state = WAIT_PACKET; // restart if not found
break;
case WAIT_PACK_ALR2: // wait for 2nd char
if (rl == PACK_ALR)
state = WAIT_PACK_ALR3;
else
state = WAIT_PACKET; // restart if not found
break;
case WAIT_PACK_ALR3: // wait for 3rd char
if (rl == PACK_ALR)
{
state = READ_VALUE; // ready to read values from PACK_ALR packet
rpack = PACK_ALR;
rval = 1;
for (i = 0; i < NB_BUF; i++)
ibuf[i] = 0;
}
else
state = WAIT_PACKET; // restart if not found
break;
case WAIT_PACK_PRF2: // wait for 2nd char
if (rl == PACK_PRF)
state = WAIT_PACK_PRF3;
else
state = WAIT_PACKET; // restart if not found
break;
case WAIT_PACK_PRF3: // wait for 3rd char
if (rl == PACK_PRF)
{
state = READ_VALUE; // ready to read values from PACK_PRF packet
rpack = PACK_PRF;
rval = 1;
for (i = 0; i < NB_BUF; i++)
ibuf[i] = 0;
}
else
state = WAIT_PACKET; // restart if not found
break;
case FLUSH_TITLE1: // wait for 1st char of title
state = FLUSH_TITLE2;
break;
case FLUSH_TITLE2: // wait for 2nd char
state = FLUSH_TITLE3;
break;
case FLUSH_TITLE3: // wait for 3rd char
state = FLUSH_TITLE4;
break;
case FLUSH_TITLE4: // wait for 4th char
if (rl == TITLE_END)
state = READ_VALUE;
else
state = WAIT_PACKET; // was not a title, wait for the next packet
break;
case READ_VALUE:
switch (rl)
{
case PACK_END:
state = WAIT_PACKET; // packet completed, wait for the next packet
break;
case VAL_END: // comma found, value completed
state = FLUSH_TITLE1; // flush next title
rval++; // and get next value
break;
default: // store the char in the corresponding buffer
for (i = 0; i < NB_BUF; i++)
{ // is it the expected value in the expected packet ?
if (rpack == xpack[i] && rval == xval[i] && ibuf[i] < LG_BUF - 1)
{ // yes, store the char
rbuf[i] [ibuf[i]] = rl;
ibuf[i]++;
rbuf[i] [ibuf[i]] = 0;
}
}
break;
}
break;
}
}
#endif
void ARDUPILOT_Init (void)
{
DDRE &= ~(1 << DDE0); // set RXD0 pin as input
PORTE &= ~(1 << PORTE0); // disable pullup on RXD0 pin
#ifndef SIMU
// switch (Telem_baud)
// {
// case 1:
#undef BAUD
#define BAUD 38400
#include <util/setbaud.h>
UBRR0H = UBRRH_VALUE;
UBRR0L = UBRRL_VALUE;
// break;
// }
UCSR0A &= ~(1 << U2X0); // disable double speed operation
// set 8N1
UCSR0B = 0|(0<< RXCIE0)|(0<<TXCIE0)|(0<<UDRIE0)|(0<<RXEN0)|(0<<TXEN0)|(0<<UCSZ02);
UCSR0C = 0|(1 << UCSZ01) | (1 << UCSZ00);
while ( UCSR0A & (1 << RXC0) )
UDR0; // flush receive buffer
#endif
}
void ARDUPILOT_DisableTXD (void)
{
UCSR0B &= ~(1 << TXEN0); // disable TX
}
void ARDUPILOT_EnableTXD (void)
{
UCSR0B |= (1 << TXEN0); // enable TX
}
void ARDUPILOT_DisableRXD (void)
{
UCSR0B &= ~(1 << RXEN0); // disable RX
UCSR0B &= ~(1 << RXCIE0); // disable Interrupt
}
void ARDUPILOT_EnableRXD (void)
{
for (i = 0; i < NB_BUF; i++)
{
ibuf[i] = 0;
rbuf[i][0] = 0;
xpack[i] = 0;
xval[i] = 0;
}
state = WAIT_PACKET; // wait for the next packet
UCSR0B |= (1 << RXEN0); // enable RX
UCSR0B |= (1 << RXCIE0); // enable Interrupt
}
void menuViewTelemetryArduPilot(event_t event)
{
menuViewTelemetryArduPilot1(event);
}
// Start of ArduPilot menus 1-8 <<<<<<<<<<<<<<<<<<<<<<<<<<<
void menuViewTelemetryArduPilot1(event_t event)
{
switch(event) // new event received, branch accordingly
{
case EVT_KEY_FIRST(KEY_UP):
chainMenu(menuViewTelemetryArduPilot8);
break;
case EVT_KEY_FIRST(KEY_DOWN):
chainMenu(menuViewTelemetryArduPilot2);
break;
case EVT_KEY_FIRST(KEY_MENU):
ARDUPILOT_DisableRXD();
chainMenu(menuStatisticsView);
break;
case EVT_KEY_FIRST(KEY_EXIT):
ARDUPILOT_DisableRXD();
chainMenu(menuMainView);
break;
}
/*
How to use:
You choose the values to be displayed using the function:
initval(<number>, <packet>, <value>);
-------------------------------------
That means that "<value>" of "<packet>" is stored in the <number> buffer.
The first <number> is 0.
Here are the packet names and the associated value names:
Position packet (beginning with "!!!"): "PACK_POS"
value names: "LAT", "LON", "SPD", "CRT", "ALT", "ALH", "CRS", "BER",
"WPN", "DST", "BTV", "RSP", "TOW"
Attitude packet (beginning with "+++"): "PACK_ATT"
value names: "ASP", "THH", "RLL", "PCH"
Mode change packet (beginning with "###"): "PACK_MOD"
value name: "MOD"
Waypoint packet (beginning with "%%%"): "PACK_WPC"
value name: "WPC"
Alert packet (beginning with "XXX"): "PACK_ALR"
value name: "ALR"
Performance packet (beginning with "PPP"): "PACK_PRF"
value name: "PRF"
The buffers are accessed using the macro "VALSTR(<n>)", where "<n>" is "0"
for the first buffer, and "1" for the second buffer.
When a value is missing, it is replaced by the contents of val_unknown ("?").
*/
// expecting LAT value in POS packet to be stored in the first buffer
initval (0, PACK_POS, LAT);
// and LON value in POS packet stored in the second buffer
initval (1, PACK_POS, LON);
// title of the screen
title ('1');
lcdDrawText(5*FW, 1*FH, PSTR(" Latitude")); // line 1 column 5
// first buffer into line 2 column 2
lcdDrawText (2*FW, 2*FH, VALSTR(0), APSIZE);
lcdDrawText(5*FW, 4*FH, PSTR(" Longitude")); // line 4 column 5
// second buffer into line 5 column 2
lcdDrawText (1*FW, 5*FH, VALSTR(1), APSIZE);
}
void menuViewTelemetryArduPilot2(event_t event)
{
switch(event)
{
case EVT_KEY_FIRST(KEY_UP):
chainMenu(menuViewTelemetryArduPilot1);
break;
case EVT_KEY_FIRST(KEY_DOWN):
chainMenu(menuViewTelemetryArduPilot3);
break;
case EVT_KEY_FIRST(KEY_EXIT):
ARDUPILOT_DisableRXD();
chainMenu(menuMainView);
break;
}
initval (0, PACK_POS, SPD);
initval (1, PACK_POS, CRT);
title ('2');
lcdDrawText(1*FW, 1*FH, PSTR(" Ground speed"));
lcdDrawText (2*FW, 2*FH, VALSTR(0), APSIZE);
lcdDrawText(1*FW, 4*FH, PSTR(" Climb rate") );
lcdDrawText (2*FW, 5*FH, VALSTR(1), APSIZE);
}
void menuViewTelemetryArduPilot3(event_t event)
{
switch(event)
{
case EVT_KEY_FIRST(KEY_UP):
chainMenu(menuViewTelemetryArduPilot2);
break;
case EVT_KEY_FIRST(KEY_DOWN):
chainMenu(menuViewTelemetryArduPilot4);
break;
case EVT_KEY_FIRST(KEY_EXIT):
ARDUPILOT_DisableRXD();
chainMenu(menuMainView);
break;
}
initval (0, PACK_POS, ALT);
initval (1, PACK_POS, ALH);
title ('3');
lcdDrawText(1*FW, 1*FH, PSTR(" Altitude"));
lcdDrawText (2*FW, 2*FH, VALSTR(0), APSIZE);
lcdDrawText(1*FW, 4*FH, PSTR(" Altitude Hold") );
lcdDrawText (2*FW, 5*FH, VALSTR(1), APSIZE);
}
void menuViewTelemetryArduPilot4(event_t event)
{
switch(event)
{
case EVT_KEY_FIRST(KEY_UP):
chainMenu(menuViewTelemetryArduPilot3);
break;
case EVT_KEY_FIRST(KEY_DOWN):
chainMenu(menuViewTelemetryArduPilot5);
break;
case EVT_KEY_FIRST(KEY_EXIT):
ARDUPILOT_DisableRXD();
chainMenu(menuMainView);
break;
}
initval (0, PACK_POS, CRS);
initval (1, PACK_POS, BER);
title ('4');
lcdDrawText(1*FW, 1*FH, PSTR(" Course"));
lcdDrawText (2*FW, 2*FH, VALSTR(0), APSIZE);
lcdDrawText(1*FW, 4*FH, PSTR(" Bearing"));
lcdDrawText (2*FW, 5*FH, VALSTR(1), APSIZE);
}
void menuViewTelemetryArduPilot5(event_t event)
{
switch(event)
{
case EVT_KEY_FIRST(KEY_UP):
chainMenu(menuViewTelemetryArduPilot4);
break;
case EVT_KEY_FIRST(KEY_DOWN):
chainMenu(menuViewTelemetryArduPilot6);
break;
case EVT_KEY_FIRST(KEY_MENU):
break;
case EVT_KEY_FIRST(KEY_EXIT):
ARDUPILOT_DisableRXD();
chainMenu(menuMainView);
break;
}
initval (0, PACK_POS, WPN);
initval (1, PACK_POS, DST);
title ('5');
lcdDrawText(1*FW, 1*FH, PSTR(" Way Point # "));
lcdDrawText (2*FW, 2*FH, VALSTR(0), APSIZE);
lcdDrawText(1*FW, 4*FH, PSTR(" Distance "));
lcdDrawText (2*FW, 5*FH, VALSTR(1), APSIZE);
}
void menuViewTelemetryArduPilot6(event_t event)
{
switch(event)
{
case EVT_KEY_FIRST(KEY_UP):
chainMenu(menuViewTelemetryArduPilot5);
break;
case EVT_KEY_FIRST(KEY_DOWN):
chainMenu(menuViewTelemetryArduPilot7);
break;
case EVT_KEY_FIRST(KEY_MENU):
break;
case EVT_KEY_FIRST(KEY_EXIT):
ARDUPILOT_DisableRXD();
chainMenu(menuMainView);
break;
}
initval (0, PACK_ATT, ASP);
initval (1, PACK_ATT, THH);
title ('6');
lcdDrawText(1*FW, 1*FH, PSTR(" Air Speed "));
lcdDrawText (2*FW, 2*FH, VALSTR(0), APSIZE);
lcdDrawText(1*FW, 4*FH, PSTR(" Climb Rate "));
lcdDrawText (2*FW, 5*FH, VALSTR(1), APSIZE);
}
void menuViewTelemetryArduPilot7(event_t event)
{
switch(event)
{
case EVT_KEY_FIRST(KEY_UP):
chainMenu(menuViewTelemetryArduPilot6);
break;
case EVT_KEY_FIRST(KEY_DOWN):
chainMenu(menuViewTelemetryArduPilot8);
break;
case EVT_KEY_FIRST(KEY_MENU):
break;
case EVT_KEY_FIRST(KEY_EXIT):
ARDUPILOT_DisableRXD();
chainMenu(menuMainView);
break;
}
initval (0, PACK_ATT, RLL);
initval (1, PACK_ATT, PCH);
title ('7');
lcdDrawText(1*FW, 1*FH, PSTR(" Roll Angle"));
lcdDrawText (2*FW, 2*FH, VALSTR(0), APSIZE);
lcdDrawText(1*FW, 4*FH, PSTR(" Pitch Angle"));
lcdDrawText (2*FW, 5*FH, VALSTR(1), APSIZE);
}
void menuViewTelemetryArduPilot8(event_t event)
{
switch(event)
{
case EVT_KEY_FIRST(KEY_UP):
chainMenu(menuViewTelemetryArduPilot7);
break;
case EVT_KEY_FIRST(KEY_DOWN):
chainMenu(menuViewTelemetryArduPilot1);
break;
case EVT_KEY_FIRST(KEY_MENU):
break;
case EVT_KEY_FIRST(KEY_EXIT):
ARDUPILOT_DisableRXD();
chainMenu(menuMainView);
break;
}
initval (0, PACK_MOD, MOD);
initval (1, PACK_WPC, WPC);
title ('8');
lcdDrawText(1*FW, 1*FH, PSTR(" ArduPilot Mode"));
lcdDrawText (2*FW, 2*FH, VALSTR(0), APSIZE);
lcdDrawText(1*FW, 4*FH, PSTR(" RTL Distance"));
lcdDrawText (2*FW, 5*FH, VALSTR(1), APSIZE);
}
void title(char x)
{
lcdDrawText (0, 0, PSTR(" ARDU PILOT Mega ?/8 "), INVERS);
lcdDrawChar(17*FW, 0*FH, x, INVERS);
}
void initval(uint8_t num, uint8_t pack, uint8_t val)
{
if (xpack[num] != pack || xval[num] != val)
{
ibuf[num] = rbuf[num][0] = 0;
xpack[num] = pack;
xval[num] = val;
state = WAIT_PACKET; // synchronize to the next packet
}
}
/*
Without ArduPilot:
Size after:
er9x.elf :
section size addr
.data 164 8388864
.text 50634 0
.bss 3485 8389028
----------------------------------
With ArduPilot:
Size after:
er9x.elf :
section size addr
.data 166 8388864
.text 53026 0
.bss 3517 8389030
*/

View file

@ -1,27 +0,0 @@
/*
* 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.
*/
#ifndef _ARDUPILOT_H_
#define _ARDUPILOT_H_
void ARDUPILOT_Init(void);
void ARDUPILOT_EnableRXD (void);
void menuViewTelemetryArduPilot(event_t event);
#endif // _ARDUPILOT_H_

View file

@ -21,16 +21,7 @@
#include "opentx.h"
#if defined(TELEMETREZ)
#define PRIVATE 0x1B
uint8_t privateDataLen;
uint8_t privateDataPos;
#endif
#if defined(ROTARY_ENCODER_NAVIGATION) && defined(TELEMETREZ)
extern uint8_t TrotCount;
extern uint8_t TezRotary;
#endif
NOINLINE void processFrskyTelemetryData(uint8_t data)
{
@ -102,42 +93,8 @@ NOINLINE void processFrskyTelemetryData(uint8_t data)
telemetryRxBufferCount = 0;
dataState = STATE_DATA_START;
}
#if defined(TELEMETREZ)
if (data == PRIVATE) {
dataState = STATE_DATA_PRIVATE_LEN;
}
#endif
break;
#if defined(TELEMETREZ)
case STATE_DATA_PRIVATE_LEN:
dataState = STATE_DATA_PRIVATE_VALUE;
privateDataLen = data; // Count of bytes to receive
privateDataPos = 0;
break;
case STATE_DATA_PRIVATE_VALUE :
if (privateDataPos == 0) {
// Process first private data byte
// PC6, PC7
if ((data & 0x3F) == 0) {// Check byte is valid
DDRC |= 0xC0; // Set as outputs
PORTC = ( PORTC & 0x3F ) | ( data & 0xC0 ); // update outputs
}
}
#if defined(ROTARY_ENCODER_NAVIGATION)
if (privateDataPos == 1) {
TrotCount = data;
}
if (privateDataPos == 2) { // rotary encoder switch
RotEncoder = data;
}
#endif
if (++privateDataPos == privateDataLen) {
dataState = STATE_DATA_IDLE;
}
break;
#endif
} // switch
#if defined(TELEMETRY_FRSKY_SPORT)

View file

@ -30,10 +30,6 @@ enum FrSkyDataState {
STATE_DATA_START,
STATE_DATA_IN_FRAME,
STATE_DATA_XOR,
#if defined(TELEMETREZ)
STATE_DATA_PRIVATE_LEN,
STATE_DATA_PRIVATE_VALUE
#endif
};
#define FRSKY_SPORT_BAUDRATE 57600

View file

@ -1,826 +0,0 @@
/*
* 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"
#define LG_BUF 14
#define NB_LONG_BUF 3
#define NB_SHORT_BUF 3
#define LONG_BUF(val) (val)
#define SHORT_BUF(val) (val+NB_LONG_BUF)
#define VALSTR(val) (rbuf[val][0] ? rbuf[val] : val_unknown)
#define APSIZE (BSS | DBLSIZE)
uint8_t i; // working variable
uint8_t state; // currrent state
uint8_t rval, rpack; // received items
uint8_t xval[NB_LONG_BUF+NB_SHORT_BUF]; // expected value
uint8_t xpack[NB_LONG_BUF+NB_SHORT_BUF]; // expected packet
uint8_t ibuf[NB_LONG_BUF]; // subscripts on long buffers values
char rbuf[NB_LONG_BUF][LG_BUF]; // long receive buffers
char sbuf[NB_SHORT_BUF]; // short receive buffers
const char val_unknown[] = "?";
int32_t home_alt, save_alt, rel_alt, prev_alt, lift_alt, max_alt, abs_alt; // integer values for altitude computations
int32_t gpstimer=0;
int32_t gpstime;
uint8_t ggareceived;
uint8_t beep_on;
uint8_t show_timer;
/* Received data
Data are received as packets, each packet is identified by a prefix of seven
characters ('$GPGGA,' or '$GPRMC,')and is ended by one star plus two bytes checksum.
The values are terminated by a comma.
$GPGGA - Global Positioning System Fix Data, Time, Position and fix related data fora GPS receiver.
11
1 2 3 4 5 6 7 8 9 10 | 12 13 14 15
| | | | | | | | | | | | | | |
GGA,hhmmss.ss,llll.ll,a,yyyyy.yy,a,x,xx,x.x,x.x,M,x.x,M,x.x,xxxx*hh<CR><LF>
Field Number:
1) Universal Time Coordinated (UTC)
2) Latitude
3) N or S (North or South)
4) Longitude
5) E or W (East or West)
6) GPS Quality Indicator,
0 - fix not available,
1 - GPS fix,
2 - Differential GPS fix
7) Number of satellites in view, 00 - 12
8) Horizontal Dilution of precision
9) Antenna Altitude above/below mean-sea-level (geoid)
10) Units of antenna altitude, meters
11) Geoidal separation, the difference between the WGS-84 earth
ellipsoid and mean-sea-level (geoid), "-" means mean-sea-level
below ellipsoid
12) Units of geoidal separation, meters
13) Age of differential GPS data, time in seconds since last SC104
type 1 or 9 update, null field when DGPS is not used
14) Differential reference station ID, 0000-1023
*
15) Checksum
CrLf
$GPRMC - Recommended Minimum Navigation Information
12
1 2 3 4 5 6 7 8 9 10 11|
| | | | | | | | | | | |
RMC,hhmmss.ss,A,llll.ll,a,yyyyy.yy,a,x.x,x.x,xxxx,x.x,a*hh<CR><LF>
Field Number:
1) UTC Time
2) Status, V = Navigation receiver warning
3) Latitude
4) N or S
5) Longitude
6) E or W
7) Speed over ground, knots
8) Track made good, degrees true. = = Course over ground (COG)
9) Date, ddmmyy
10) Magnetic Variation, degrees
11) E or W
12) Checksum
*/
// GGA record prefix
#define PACK_GGA 0x47 // "G"
#define PACK_GGA3 0x41 // "A"
// value occurence number in the GGA packet
#define TIM 1
#define LAT 2
#define NOS 3
#define LON 4
#define EOW 5
#define FIX 6
#define SAT 7
#define DIL 8
#define ALT 9
#define MTR 10
#define GEO 11
#define MET 12
#define AGE 13
#define DIF 14
// RMC record prefix
#define PACK_RMC 0x52 // "R"
#define PACK_RMC2 0x4D // "M"
#define PACK_RMC3 0x43 // "C"
// value occurence number in the RMC packet
#define TIM 1
#define NRW 2
#define LT1 3
#define NSO 4
#define LN1 5
#define EWE 6
#define SOG 7
#define COG 8
#define DAT 9
#define MAG 10
#define EAW 11
// end of packet
#define PACK_END 0x2a // *
// end of value
#define VAL_END 0x2c // ,
// stateful machine
// Since the packets are sent continuously, we need to synchronize on the
// reception of the three chars prefixing a packet, whatever they are.
// states values
#define WAIT_PACKET 1
#define WAIT_PACK_GGA1 2
#define WAIT_PACK_GGA2 3
#define WAIT_PACK_GGA3 4
#define WAIT_PACK_RMC2 5
#define WAIT_PACK_RMC3 6
#define WAIT_VAL_END 7
#define READ_VALUE 8
void menuViewTelemetryNMEA1(event_t event);
void menuViewTelemetryNMEA2(event_t event);
void menuViewTelemetryNMEA3(event_t event);
void menuViewTelemetryNMEA4(event_t event);
void title(char x);
void initval(uint8_t num, uint8_t pack, uint8_t val);
int32_t binary (char *str);
int32_t bintime (char *str);
#ifndef SIMU
ISR (USART0_RX_vect)
{
uint8_t rl;
// uint8_t rh; //USART control and Status Register 0 B
uint8_t iostat; //USART control and Status Register 0 A
rl = UDR0;
iostat = UCSR0A; //USART control and Status Register 0 A
/*
bit 7 6 5 4 3 2 1 0
RxC0 TxC0 UDRE0 FE0 DOR0 UPE0 U2X0 MPCM0
RxC0: Receive complete
TXC0: Transmit Complete
UDRE0: USART Data Register Empty
FE0: Frame Error
DOR0: Data OverRun
UPE0: USART Parity Error
U2X0: Double Tx Speed
MPCM0: MultiProcessor Comms Mode
*/
if (iostat & ((1 << FE0) | (1 << DOR0) | (1 << UPE0)))
{
rl = xpack[0] = xpack[1] = xval[0] = xval[1] = 0;
initval (LONG_BUF(2), PACK_GGA, TIM); // always get UTC time for timer
state = WAIT_PACKET; // restart on error
}
// rh = UCSR0B; //USART control and Status Register 0 B
/* bit 7 6 5 4 3 2 1 0
RxCIE0 TxCIE0 UDRIE0 RXEN0 TXEN0 UCSZ02 RXB80 TXB80
RxCIE0: Receive complete int enable
TXCIE0: Transmit Complete int enable
UDRIE0: USART Data Register Empty int enable
RXEN0: Rx enable
TXEN0: Tx Enable
UCSZ02: Character Size bit 2
RXB80: Rx data bit 8
TXB80: Tx data bit 8
*/
switch (state)
{
case WAIT_PACKET:
switch (rl)
{
case PACK_GGA: // found a new GGA packet "G"
state = WAIT_PACK_GGA2; // wait for the 2nd char
break;
case PACK_RMC: // found a new RMS packet "R"
state = WAIT_PACK_RMC2; // wait for the 2nd char
break;
}
break;
case WAIT_PACK_GGA2: // received 2nd char "G"
if (rl == PACK_GGA)
state = WAIT_PACK_GGA3; // wait for 3rd character "A"
else
state = WAIT_PACKET; // restart if not "G"
break;
case WAIT_PACK_GGA3: // received 3rd char "A"
if (rl == PACK_GGA3) // found
{
state = WAIT_VAL_END; // wait for ","
rpack = PACK_GGA;
rval = 1; //clear the buffer
for (i = 0; i < NB_LONG_BUF; i++)
ibuf[i] = 0;
}
else
state = WAIT_PACKET; // restart if not found
break;
case WAIT_PACK_RMC2: // wait for 2nd char "M"
if (rl == PACK_RMC2)
state = WAIT_PACK_RMC3;
else
state = WAIT_PACKET; // restart if not found
break;
case WAIT_PACK_RMC3: // wait for 3rd char "C"
if (rl == PACK_RMC3)
{
state = WAIT_VAL_END; // wait for ","
rpack = PACK_RMC;
rval = 1;
for (i = 0; i < NB_LONG_BUF; i++) // clear buffer
ibuf[i] = 0;
}
else
state = WAIT_PACKET; // restart if not found
break;
case WAIT_VAL_END:
if (rl == VAL_END) // "," nach "GGA" oder "RMC"
{
state = READ_VALUE;
rval = 1;
for (i = 0; i < NB_LONG_BUF; i++) // clear buffer
ibuf[i] = 0;
}
else
state = WAIT_PACKET; // restart if not found
break;
case READ_VALUE:
switch (rl)
{
case PACK_END:
if (rpack == PACK_GGA)
ggareceived = 1;
state = WAIT_PACKET; // packet completed, wait for the next packet
break;
case VAL_END: // comma found, value completed
rval++; // and get next value
break;
default: // store the char in the corresponding buffer
for (i = 0; i < NB_LONG_BUF; i++)
{ // is it the expected value in the expected packet ?
if (rpack == xpack[i] && rval == xval[i] && ibuf[i] < LG_BUF - 1)
{ // yes, store the char
rbuf[i] [ibuf[i]] = rl;
ibuf[i]++;
rbuf[i] [ibuf[i]] = 0;
}
}
for (i = NB_LONG_BUF; i < NB_LONG_BUF+NB_SHORT_BUF; i++) {
if (rpack == xpack[i] // is this the expected short value in the expected packet ?
&& rval == xval[i])
sbuf[i-NB_LONG_BUF] = rl; // yes, store the char
}
}
break;
}
}
#endif
void NMEA_Init (void)
{
#ifndef SIMU
DDRE &= ~(1 << DDE0); // set RXD0 pin as input
PORTE &= ~(1 << PORTE0); // disable pullup on RXD0 pin
// switch (Telem_baud)
// {
// case 1:
#undef BAUD
#define BAUD 4800
#include <util/setbaud.h>
UBRR0H = UBRRH_VALUE;
UBRR0L = UBRRL_VALUE;
// break;
// }
UCSR0A &= ~(1 << U2X0); // disable double speed operation
// set 8N1
UCSR0B = 0|(0<< RXCIE0)|(0<<TXCIE0)|(0<<UDRIE0)|(0<<RXEN0)|(0<<TXEN0)|(0<<UCSZ02);
UCSR0C = 0|(1 << UCSZ01) | (1 << UCSZ00);
while ( UCSR0A & (1 << RXC0) )
UDR0; // flush receive buffer
#endif
home_alt = rel_alt = ggareceived =0;
gpstimer = -1;
beep_on=1;
}
// TX Capabilities are not required for NMEA
// void NMEA_DisableTXD (void)
// {
// UCSR0B &= ~(1 << TXEN0); // disable TX
// }
// void NMEA_EnableTXD (void)
// {
// UCSR0B |= (1 << TXEN0); // enable TX
// }
void NMEA_DisableRXD (void)
{
UCSR0B &= ~(1 << RXEN0); // disable RX
UCSR0B &= ~(1 << RXCIE0); // disable Interrupt
}
void NMEA_EnableRXD (void)
{
for (i = 0; i < NB_LONG_BUF; i++)
{
ibuf[i] = 0;
rbuf[i][0] = 0;
xpack[i] = 0;
xval[i] = 0;
}
initval (LONG_BUF(2), PACK_GGA, TIM); // always get UTC time for timer
state = WAIT_PACKET; // wait for the next packet
UCSR0B |= (1 << RXEN0); // enable RX
UCSR0B |= (1 << RXCIE0); // enable Interrupt
}
void menuViewTelemetryNMEA(event_t event)
{
menuViewTelemetryNMEA1(event);
}
// Start of NMEA menus 1-4 <<<<<<<<<<<<<<<<<<<<<<<<<<<
void menuViewTelemetryNMEA1(event_t event)
{
switch(event) // new event received, branch accordingly
{
case EVT_KEY_BREAK(KEY_LEFT):
chainMenu(menuViewTelemetryNMEA4);
break;
case EVT_KEY_BREAK(KEY_RIGHT):
chainMenu(menuViewTelemetryNMEA2);
break;
case EVT_KEY_LONG(KEY_UP):
NMEA_DisableRXD();
chainMenu(menuStatisticsView);
break;
case EVT_KEY_LONG(KEY_DOWN):
NMEA_DisableRXD();
chainMenu(menuMainView);
break;
case EVT_KEY_FIRST(KEY_MENU):
if (show_timer == 0) {
show_timer = 1;
if (gpstimer <= 0)
gpstimer = bintime(rbuf[2]);
}
else
show_timer = 0;
break;
case EVT_KEY_FIRST(KEY_EXIT):
if ((show_timer == 1) &&(rbuf[2][0]))
gpstimer = bintime(rbuf[2]); // get actual GPS time ->resets timer to 00:00
break;
}
/*
How to use:
You choose the values to be displayed using the function:
initval(<number>, <packet>, <value>);
-------------------------------------
That means that "<value>" of "<packet>" is stored in the <number> buffer.
The first <number> is 0.
Here are the packet names and the associated value names:
Position packet (beginning with "GGA"): "PACK_GGA"
value names: "TIM", "LAT", "NOS", "LON", "EOW", "FIX", "SAT", "DIL", "ALT", "MTR", "GEO", "MET", "AGE", "DIF",
Required minimum packet (beginning with "RMC"): "PACK_RMC"
value names: "TIM", "NRW", "LT1", "NSO", "LN1", "EWE", "SOG", "COG", "DAT", "MAG", "EAW"
The buffers are accessed using the macro "VALSTR(<n>)", where "<n>" is "0"
for the first buffer, and "1" for the second buffer.
When a value is missing, it is replaced by the contents of val_unknown ("?").
*/
if (ggareceived)
{
gpstime=bintime(rbuf[2]);
ggareceived=0;
}
initval (LONG_BUF(0), PACK_RMC, TIM); // sets rbuf[0][.]
initval (LONG_BUF(1), PACK_RMC, DAT); // sets rbuf[1][.]
initval (SHORT_BUF(0), PACK_RMC, NRW); // sets sbuf[0]
initval (SHORT_BUF(2), PACK_GGA, SAT); // -> sbuf[2]
title ('1');
lcdDrawText ( 2*FW, 1*FH, PSTR("UTC-Time Sat"));
if (rbuf[0][0]) { // show always if data have been received
lcdDrawChar ( 19*FW, 1*FH, sbuf[2], 0); // satellites in view
lcdDrawSizedText ( 2*FW, 2*FH, &rbuf[0][0], 2, APSIZE); // hours
lcdDrawChar ( 6*FW, 2*FH, ':', DBLSIZE); // ":"
lcdDrawSizedText ( 8*FW, 2*FH, &rbuf[0][2], 2, APSIZE); // minutes
lcdDrawChar ( 12*FW, 2*FH, ':', DBLSIZE); // ":"
lcdDrawSizedText ( 14*FW, 2*FH, &rbuf[0][4], 2, APSIZE); // seconds
}
else
lcdDrawText ( 2*FW, 2*FH, val_unknown, APSIZE); // "?"
if ((show_timer == 1) && rbuf[0][0]) { // show the Timer when data have been received
lcdDrawText ( 2*FW, 4*FH, PSTR("Timer")); // display "Timer"
drawTimer ( 5*FW, 5*FH, (gpstime-gpstimer), DBLSIZE, DBLSIZE); // display difference as mm:ss
}
else
{
lcdDrawText ( 2*FW, 4*FH, PSTR("Date")); // show the UTC Date
if (rbuf[1][0]) {
lcdDrawSizedText( 2*FW, 5*FH, &rbuf[1][0], 2, APSIZE); // year
lcdDrawChar ( 6*FW, 5*FH, '/', DBLSIZE); // "/"
lcdDrawSizedText( 8*FW, 5*FH, &rbuf[1][2], 2, APSIZE); // month
lcdDrawChar (12*FW, 5*FH, '/', DBLSIZE); // "/"
lcdDrawSizedText(14*FW, 5*FH, &rbuf[1][4], 2, APSIZE); // day
}
else
lcdDrawText ( 2*FW, 5*FH, val_unknown, APSIZE); // "?"
}
}
void menuViewTelemetryNMEA2(event_t event)
{
static uint8_t ignore_break;
switch(event)
{
// Menu navigation
case EVT_KEY_BREAK(KEY_LEFT):
if (ignore_break==1) {
ignore_break=0;
break;}
chainMenu(menuViewTelemetryNMEA1);
break;
case EVT_KEY_BREAK(KEY_RIGHT):
if (ignore_break==1) {
ignore_break=0;
break;}
chainMenu(menuViewTelemetryNMEA3);
break;
case EVT_KEY_LONG(KEY_UP):
NMEA_DisableRXD();
chainMenu(menuStatisticsView);
break;
case EVT_KEY_LONG(KEY_DOWN):
NMEA_DisableRXD();
chainMenu(menuMainView);
break;
//Beep setting
case EVT_KEY_LONG(KEY_LEFT):
ignore_break = 1;
beep_on=0;
AUDIO_KEY_PRESS();
break;
case EVT_KEY_LONG(KEY_RIGHT):
ignore_break = 1;
beep_on=1;
AUDIO_KEY_PRESS();
break;
//Altitude setting
/* Set a home position for altitude. Normally used before starting
the model when GPS has got a fix.
MENU[short] --> alternating relative and absolute altitudes
MENU[long] --> set home altitude to current
EXIT[long] --> reset max altitude to 0
Switch ON / OFF short beep with positive lift
LEFT[long] --> Positive lift Beep off
RIGHT[long] --> Positive lift Beep on */
case EVT_KEY_BREAK(KEY_MENU):
if (ignore_break==1) {
ignore_break=0;
break;}
if (!home_alt) // umschalten zwischen absoluter und relativer H<>he
home_alt = save_alt;
else
home_alt=0;
if (save_alt==0) // wenn noch keine Home H<>he gesetzt war, wird sie es jetzt, weil sonst
// das Umschalten keine Wirkung zeigt
save_alt = home_alt = abs_alt; // absolute altitude
AUDIO_KEY_PRESS();
break;
case EVT_KEY_LONG(KEY_MENU):
ignore_break = 1;
save_alt = home_alt = abs_alt; // Home altitude auf aktuelle absolute H<>he setzen
AUDIO_KEY_PRESS();
break;
case EVT_KEY_LONG(KEY_EXIT): // Max Altitude auf 0 zur<75>cksetzen
max_alt=0;
AUDIO_KEY_PRESS();
break;
}
title ('2');
lcdDrawText ( 1*FW, 1*FH, PSTR("Altitude Sat Max"));
lcdDrawText ( 16*FW, 3*FH, PSTR("Home"));
lcdDrawText ( 2*FW, 4*FH, PSTR("Lift") );
lcdDrawText ( 16*FW, 5*FH, PSTR("Beep") );
if (beep_on==1)
lcdDrawText ( 18*FW, 6*FH, PSTR("ON") );
else
lcdDrawText ( 17*FW, 6*FH, PSTR("OFF") );
lcdDrawNumber( 20*FW, 4*FH, home_alt, PREC1, 6); // display home_alt, small characters
if (xpack[0] != PACK_GGA)
ggareceived = 0;
initval (LONG_BUF(0), PACK_GGA, ALT); // -> rbuf[0]
initval (LONG_BUF(1), PACK_GGA, GEO); // -> rbuf[1]
initval (SHORT_BUF(0), PACK_GGA, MTR); // -> sbuf[0]
initval (SHORT_BUF(1), PACK_GGA, FIX); // -> sbuf[1]
initval (SHORT_BUF(2), PACK_GGA, SAT); // -> sbuf[2]
if (ggareceived) // at least one second has elapsed
{
ggareceived = 0;
/* ALT and GEO have one single digit following the decimal point
e.g. ALT=359.7 GEO=47.7
The altitude over mean sea level is to be calculated as:
altitude minus geoidal separation
*/
abs_alt = binary(rbuf[0]) - binary(rbuf[1]); // alt - geo that is absolute altitude
if (abs_alt> max_alt) max_alt=abs_alt; // hold max altitude relative to 0 m
rel_alt=abs_alt - home_alt; // alt - geo - home altitude relative to home
lift_alt = rel_alt - prev_alt;
prev_alt = rel_alt;
if ((lift_alt >= 0) && (sbuf[1]>0x30) && beep_on) // GGA record must have Fix> 0
AUDIO_KEY_PRESS(); // short blip for non negative lift
}
if (rbuf[0][0]) {
lcdDrawChar ( 13*FW, 1*FH, sbuf[2], 0); // satellites in view
if (sbuf[1]>0x30) { // & GGA has FIX > 0
lcdDrawNumber( 10*FW, 2*FH, rel_alt, DBLSIZE|PREC1, 7); // altitude
if (home_alt >= 0)
lcdDrawNumber( 20*FW, 2*FH, (max_alt-home_alt), PREC1, 6); // display small characters
else
lcdDrawNumber( 20*FW, 2*FH, max_alt, PREC1, 6); // display small characters
lcdDrawChar ( 11*FW, 3*FH, sbuf[0], 0); // dimension [m]
lcdDrawNumber( 10*FW, 5*FH, lift_alt, DBLSIZE|PREC1, 6); // lift
lcdDrawChar ( 11*FW, 6*FH, sbuf[0], 0); // dimension [m/S]
lcdDrawText ( 12*FW, 6*FH, PSTR("/S") );
}
}
else {
lcdDrawText ( 2*FW, 2*FH, val_unknown, APSIZE);
lcdDrawText ( 2*FW, 5*FH, val_unknown, APSIZE);
}
}
void menuViewTelemetryNMEA3(event_t event)
{
switch(event)
{
case EVT_KEY_BREAK(KEY_LEFT):
chainMenu(menuViewTelemetryNMEA2);
break;
case EVT_KEY_BREAK(KEY_RIGHT):
chainMenu(menuViewTelemetryNMEA4);
break;
case EVT_KEY_LONG(KEY_UP):
NMEA_DisableRXD();
chainMenu(menuStatisticsView);
break;
case EVT_KEY_LONG(KEY_DOWN):
NMEA_DisableRXD();
chainMenu(menuMainView);
break;
}
initval (LONG_BUF(0), PACK_RMC, SOG);
initval (LONG_BUF(1), PACK_RMC, COG);
initval (SHORT_BUF(2), PACK_GGA, SAT); // -> sbuf[2]
title ('3');
lcdDrawText ( 0*FW, 1*FH, PSTR("GrndSpeed[knt] Sat"));
if (rbuf[0][0]) // if first position is 00, buffer is empty, taken as false
{ // any other value is true
uint8_t i = 0;
while (rbuf[0][i])
{
if (rbuf[0][i] == '.') // find decimal point and insert End of String 3 positions higher
{
rbuf[0][i+3] = 0;
break;
}
i++;
}
lcdDrawText ( 2*FW, 2*FH, VALSTR(0), APSIZE); // speed over ground
}
else
lcdDrawText ( 2*FW, 2*FH, val_unknown, APSIZE);
lcdDrawChar ( 19*FW, 1*FH, sbuf[2], 0); // satellites in view
lcdDrawText ( 1*FW, 4*FH, PSTR("Course over ground") );
lcdDrawText ( 2*FW, 5*FH, VALSTR(1), APSIZE); // course over ground
}
void menuViewTelemetryNMEA4(event_t event)
{
switch(event) // new event received, branch accordingly
{
case EVT_KEY_BREAK(KEY_LEFT):
chainMenu(menuViewTelemetryNMEA3);
break;
case EVT_KEY_BREAK(KEY_RIGHT):
chainMenu(menuViewTelemetryNMEA1);
break;
case EVT_KEY_LONG(KEY_UP):
NMEA_DisableRXD();
chainMenu(menuStatisticsView);
break;
case EVT_KEY_LONG(KEY_DOWN):
NMEA_DisableRXD();
chainMenu(menuMainView);
break;
}
// expecting LAT value in POS packet to be stored in the first buffer
initval (LONG_BUF(0), PACK_GGA, LAT);
initval (SHORT_BUF(0), PACK_GGA, NOS);
// and LON value in POS packet stored in the second buffer
initval (LONG_BUF(1), PACK_GGA, LON);
initval (SHORT_BUF(1), PACK_GGA, EOW);
initval (SHORT_BUF(2), PACK_GGA, SAT); // -> sbuf[2]
// title of the screen
title ('4');
lcdDrawText ( 3*FW, 1*FH, PSTR("Latitude Sat")); // line 1 column 3
// first buffer into line 2 column 2
if (rbuf[0][0])
{
lcdDrawChar ( 13*FW, 1*FH, sbuf[0], 0); // N or S
lcdDrawChar ( 19*FW, 1*FH, sbuf[2], 0); // satellites in view
lcdDrawSizedText ( 1*FW, 2*FH, rbuf[0], 2, APSIZE);
lcdDrawChar ( 5*FW, 2*FH, '@',0);
lcdDrawText ( 6*FW, 2*FH, &rbuf[0][2], APSIZE); // minutes with small decimal point
}
else
lcdDrawText ( 2*FW, 2*FH, val_unknown, APSIZE);
lcdDrawText ( 3*FW, 4*FH, PSTR("Longitude")); // line 4 column 5
// second buffer into line 5 column 2
if (rbuf[0][0])
{
lcdDrawChar ( 13*FW, 4*FH, sbuf[1], 0); // E or W
lcdDrawSizedText ( 0*FW, 5*FH, rbuf[1], 3, APSIZE);
lcdDrawChar ( 6*FW, 5*FH, '@',0);
lcdDrawText ( 7*FW, 5*FH, &rbuf[1][3], APSIZE); // minutes with small decimal point
}
else
lcdDrawText ( 2*FW, 5*FH, val_unknown, APSIZE);
}
void title(char x)
{
lcdDrawText (0*FW, 0*FH, PSTR(" GPS NMEA data ?/4 "), INVERS);
lcdDrawChar(16*FW, 0*FH, x, INVERS);
}
void initval(uint8_t num, uint8_t pack, uint8_t val)
{
if (xpack[num] != pack || xval[num] != val)
{
if (num < NB_LONG_BUF) {
ibuf[num] = rbuf[num][0] = 0;
}
else
sbuf[num-NB_LONG_BUF] = '?';
xpack[num] = pack;
xval[num] = val;
state = WAIT_PACKET; // synchronize to the next packet
}
}
int32_t binary (char *str)
{
int32_t numval = 0;
uint8_t sign = 0;
while (*str) {
if (*str == '-')
sign = 1;
else if (*str >= '0' && *str <= '9')
numval = numval * 10 + (*str - '0');
str++;
}
if (sign)
numval = -numval;
return numval;
}
int32_t bintime (char *str)
{
int32_t numval=0;
if (*str) {
numval = ((str[0] - '0') * 10l) + (str[1] - '0'); // hours
numval = numval * 3600l;
numval = numval + ((( (str[2] - '0') * 10l) + (str[3] - '0')) * 60l); // minutes
numval = numval + ((str[4] - '0') * 10l) + (str[5] - '0'); // seconds
}
return numval;
}
/*
Without NMEA:
Size after:
AVR Memory Usage
----------------
Device: atmega64
Program: 54226 bytes (82.7% Full)
(.text + .data + .bootloader)
Data: 3440 bytes (84.0% Full)
(.data + .bss + .noinit)
----------------------------------
With NMEA:
Size after:
AVR Memory Usage
----------------
Device: atmega64
Program: 57098 bytes (87.1% Full)
(.text + .data + .bootloader)
Data: 3524 bytes (86.0% Full)
(.data + .bss + .noinit)
*/

View file

@ -1,29 +0,0 @@
/*
* 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.
*/
#ifndef _NMEA_H_
#define _NMEA_H_
void NMEA_Init(void);
void NMEA_EnableRXD (void);
void menuViewTelemetryNMEA(event_t event);
#endif // _NMEA_H_

View file

@ -24,18 +24,6 @@
#if defined(TELEMETRY_FRSKY)
// FrSky Telemetry
#include "frsky.h"
#elif defined(TELEMETRY_JETI)
// Jeti-DUPLEX Telemetry
#include "jeti.h"
#elif defined(TELEMETRY_ARDUPILOT)
// ArduPilot Telemetry
#include "ardupilot.h"
#elif defined(TELEMETRY_NMEA)
// NMEA Telemetry
#include "nmea.h"
#elif defined(TELEMETRY_MAVLINK)
// Mavlink Telemetry
#include "mavlink.h"
#endif
#if defined(CROSSFIRE)

View file

@ -1,3 +0,0 @@
*~
doc/html
doc/*.log

@ -1 +0,0 @@
Subproject commit 21083c3af5f386a27d59a3ef6bff01a70991c3cb

View file

@ -113,11 +113,6 @@ const pm_char STR_OPEN9X[] PROGMEM =
ISTR(BLUETOOTH_MODES)
#endif
ISTR(VANTENNATYPES)
#if defined(TELEMETRY_MAVLINK)
ISTR(MAVLINK_BAUDS)
ISTR(MAVLINK_AC_MODES)
ISTR(MAVLINK_AP_MODES)
#endif
;
// The 0-terminated-strings
@ -719,31 +714,6 @@ const pm_char STR_BLCOLOR[] PROGMEM = TR_BLCOLOR;
const pm_char STR_BLUETOOTH_PIN_CODE[] PROGMEM = TR_BLUETOOTH_PIN_CODE;
#endif
#if defined(TELEMETRY_MAVLINK)
const pm_char STR_MAVLINK_RC_RSSI_SCALE_LABEL[] PROGMEM = TR_MAVLINK_RC_RSSI_SCALE_LABEL;
const pm_char STR_MAVLINK_PC_RSSI_EN_LABEL[] PROGMEM = TR_MAVLINK_PC_RSSI_EN_LABEL;
const pm_char STR_MAVMENUSETUP_TITLE[] PROGMEM = TR_MAVMENUSETUP_TITLE;
const pm_char STR_MAVLINK_BAUD_LABEL[] PROGMEM = TR_MAVLINK_BAUD_LABEL;
const pm_char STR_MAVLINK_INFOS[] PROGMEM = TR_MAVLINK_INFOS;
const pm_char STR_MAVLINK_MODE[] PROGMEM = TR_MAVLINK_MODE;
const pm_char STR_MAVLINK_CUR_MODE[] PROGMEM = TR_MAVLINK_CUR_MODE;
const pm_char STR_MAVLINK_ARMED[] PROGMEM = TR_MAVLINK_ARMED;
const pm_char STR_MAVLINK_BAT_MENU_TITLE[] PROGMEM = TR_MAVLINK_BAT_MENU_TITLE;
const pm_char STR_MAVLINK_BATTERY_LABEL[] PROGMEM = TR_MAVLINK_BATTERY_LABEL;
const pm_char STR_MAVLINK_RC_RSSI_LABEL[] PROGMEM = TR_MAVLINK_RC_RSSI_LABEL;
const pm_char STR_MAVLINK_PC_RSSI_LABEL[] PROGMEM = TR_MAVLINK_PC_RSSI_LABEL;
const pm_char STR_MAVLINK_NAV_MENU_TITLE[] PROGMEM = TR_MAVLINK_NAV_MENU_TITLE;
const pm_char STR_MAVLINK_COURSE[] PROGMEM = TR_MAVLINK_COURSE;
const pm_char STR_MAVLINK_HEADING[] PROGMEM = TR_MAVLINK_HEADING;
const pm_char STR_MAVLINK_BEARING[] PROGMEM = TR_MAVLINK_BEARING;
const pm_char STR_MAVLINK_ALTITUDE[] PROGMEM = TR_MAVLINK_ALTITUDE;
const pm_char STR_MAVLINK_GPS[] PROGMEM = TR_MAVLINK_GPS;
const pm_char STR_MAVLINK_NO_FIX[] PROGMEM = TR_MAVLINK_NO_FIX;
const pm_char STR_MAVLINK_SAT[] PROGMEM = TR_MAVLINK_SAT;
const pm_char STR_MAVLINK_HDOP[] PROGMEM = TR_MAVLINK_HDOP;
const pm_char STR_MAVLINK_LAT[] PROGMEM = TR_MAVLINK_LAT;
const pm_char STR_MAVLINK_LON[] PROGMEM = TR_MAVLINK_LON;
#endif
const pm_char STR_ABOUTUS[] PROGMEM = TR_ABOUTUS;
const pm_char STR_ABOUT_OPENTX_1[] PROGMEM = TR_ABOUT_OPENTX_1;

View file

@ -217,13 +217,7 @@ extern const pm_char STR_OPEN9X[];
#define OFS_VANTENNATYPES (OFS_VCELLINDEX + sizeof(TR_VCELLINDEX))
#endif
#define OFS_MAVLINK_BAUDS (OFS_VANTENNATYPES + sizeof(TR_VANTENNATYPES))
#if defined(TELEMETRY_MAVLINK)
#define OFS_MAVLINK_AC_MODES (OFS_MAVLINK_BAUDS + sizeof(TR_MAVLINK_BAUDS))
#define OFS_MAVLINK_AP_MODES (OFS_MAVLINK_AC_MODES + sizeof(TR_MAVLINK_AC_MODES))
#define OFS_SPARE (OFS_MAVLINK_AP_MODES + sizeof(TR_MAVLINK_AP_MODES))
#else
#define OFS_SPARE (OFS_MAVLINK_BAUDS)
#endif
#define STR_OFFON (STR_OPEN9X + OFS_OFFON)
#define STR_MMMINV (STR_OPEN9X + OFS_MMMINV)
@ -334,11 +328,6 @@ extern const pm_char STR_BLUETOOTH_LOCAL_ADDR[];
#define STR_BLUETOOTH_MODES (STR_OPEN9X + OFS_BLUETOOTH_MODES)
#endif
#if defined(TELEMETRY_MAVLINK)
#define STR_MAVLINK_BAUDS (STR_OPEN9X + OFS_MAVLINK_BAUDS)
#define STR_MAVLINK_AC_MODES (STR_OPEN9X + OFS_MAVLINK_AC_MODES)
#define STR_MAVLINK_AP_MODES (STR_OPEN9X + OFS_MAVLINK_AP_MODES)
#endif
// The 0-terminated-strings
#define NO_INDENT(x) (x)+LEN_INDENT
@ -986,31 +975,6 @@ extern const pm_char STR_BLCOLOR[];
extern const pm_char STR_MODULE_RANGE[];
#endif
#if defined(TELEMETRY_MAVLINK)
extern const pm_char STR_MAVLINK_RC_RSSI_SCALE_LABEL[];
extern const pm_char STR_MAVLINK_PC_RSSI_EN_LABEL[];
extern const pm_char STR_MAVMENUSETUP_TITLE[];
extern const pm_char STR_MAVLINK_BAUD_LABEL[];
extern const pm_char STR_MAVLINK_INFOS[];
extern const pm_char STR_MAVLINK_MODE[];
extern const pm_char STR_MAVLINK_CUR_MODE[];
extern const pm_char STR_MAVLINK_ARMED[];
extern const pm_char STR_MAVLINK_BAT_MENU_TITLE[];
extern const pm_char STR_MAVLINK_BATTERY_LABEL[];
extern const pm_char STR_MAVLINK_RC_RSSI_LABEL[];
extern const pm_char STR_MAVLINK_PC_RSSI_LABEL[];
extern const pm_char STR_MAVLINK_NAV_MENU_TITLE[];
extern const pm_char STR_MAVLINK_COURSE[];
extern const pm_char STR_MAVLINK_HEADING[];
extern const pm_char STR_MAVLINK_BEARING[];
extern const pm_char STR_MAVLINK_ALTITUDE[];
extern const pm_char STR_MAVLINK_GPS[];
extern const pm_char STR_MAVLINK_NO_FIX[];
extern const pm_char STR_MAVLINK_SAT[];
extern const pm_char STR_MAVLINK_HDOP[];
extern const pm_char STR_MAVLINK_LAT[];
extern const pm_char STR_MAVLINK_LON[];
#endif
extern const pm_char STR_ABOUTUS[];
extern const pm_char STR_ABOUT_OPENTX_1[];

View file

@ -137,8 +137,6 @@
#define TR_RETA123 "SVPK123LR"
#elif defined(PCBSKY9X)
#define TR_RETA123 "SVPK123a"
#elif defined(CPUM2560)
#define TR_RETA123 "SVPK123ab"
#else
#define TR_RETA123 "SVPK123"
#endif
@ -167,11 +165,7 @@
#define TR_IRPROTOS
#endif
#if defined(CPUARM)
#define TR_XPPM
#else
#define TR_XPPM "PPM16\0""PPMsim"
#endif
#define TR_VPROTOS "PPM\0 " TR_XPPM TR_PXX TR_DSM2 TR_IRPROTOS
@ -208,27 +202,14 @@
#else
#define TR_CSWTIMER "Tim\0 "
#define TR_CSWSTICKY "Stky\0"
#if defined(CPUARM)
#define TR_CSWRANGE "Rnge\0"
#define TR_CSWSTAY "Edge\0"
#else
#define TR_CSWRANGE
#define TR_CSWSTAY
#endif
#endif
#if defined(CPUARM)
#define TR_CSWEQUAL "a=x\0 "
#else
#define TR_CSWEQUAL
#endif
#define LEN_VCSWFUNC "\005"
#if defined(CPUARM)
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""Δ}x\0 ""|Δ|}x" TR_CSWTIMER TR_CSWSTICKY
#else
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""^}x\0 ""|^|}x" TR_CSWTIMER TR_CSWSTICKY
#endif
#define LEN_VFSWFUNC "\013"
@ -304,13 +285,7 @@
#define TR_SF_RESERVE "[rezerva]\0 "
#if defined(CPUARM)
#define TR_VFSWFUNC TR_SF_SAFETY "Trenér \0 ""Insta-Trim\0""Reset\0 ""Změna \0 " TR_ADJUST_GVAR "Hlasitost\0 " "SetFailsafe" "RangeCheck\0" "ModuleBind\0" TR_SOUND TR_PLAY_TRACK TR_PLAY_VALUE TR_SF_RESERVE TR_SF_PLAY_SCRIPT TR_SF_RESERVE TR_SF_BG_MUSIC TR_VVARIO TR_HAPTIC TR_SDCLOGS "Podsvětlení" TR_SF_SCREENSHOT TR_SF_TEST
#elif defined(PCBGRUVIN9X)
#define TR_VFSWFUNC TR_SF_SAFETY "Trenér \0 ""Insta-Trim\0""Reset\0 " TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC TR_SDCLOGS "Podsvětlení" TR_SF_TEST
#else
#define TR_VFSWFUNC TR_SF_SAFETY "Trenér \0 ""Insta-Trim\0""Reset\0 " TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC "Podsvětlení" TR_SF_TEST
#endif
#define LEN_VFSWRESET TR("\004", "\012")
@ -330,10 +305,8 @@
#if LCD_W >= 212
#define TR_FSW_RESET_TIMERS "Stopky1\0 ""Stopky2\0 ""Stopky3\0 "
#elif defined(CPUARM)
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#else
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2"
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#endif
#define TR_VFSWRESET TR(TR_FSW_RESET_TIMERS "Vše\0" TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC, TR_FSW_RESET_TIMERS "Vše\0 " TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC)
@ -348,22 +321,10 @@
#define LENGTH_UNIT_METR "m\0 "
#define SPEED_UNIT_METR "kmh"
#if defined(CPUARM)
#define LEN_VUNITSSYSTEM TR("\006", "\010")
#define TR_VUNITSSYSTEM TR("Metr.\0""Imper.", "Metrické""Imperial")
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "-\0 ""V\0 ""A\0 ""mA\0""kts""m/s""f/s""kmh""mph""m\0 ""ft\0""@C\0""@F\0""%\0 ""mAh""W\0 ""mW\0""dB\0""rpm""g\0 ""@\0 ""rad""ml\0""fOz"
#else
#if defined(IMPERIAL_UNITS)
#define LENGTH_UNIT LENGTH_UNIT_IMP
#define SPEED_UNIT SPEED_UNIT_IMP
#else
#define LENGTH_UNIT LENGTH_UNIT_METR
#define SPEED_UNIT SPEED_UNIT_METR
#endif
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "V\0 ""A\0 ""m/s""-\0 " SPEED_UNIT LENGTH_UNIT "@\0 ""%\0 ""mA\0""mAh""W\0 "
#endif
#define STR_V (STR_VTELEMUNIT+1)
#define STR_A (STR_VTELEMUNIT+4)
@ -377,15 +338,10 @@
#define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "---\0 ""Hub\0 ""WSHHigh"
#if defined(CPUARM)
#define LEN_AMPSRC TR("\003", "\005")
#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")
#define LEN_VOLTSRC TR("\003", "\005")
#define TR_VOLTSRC TR("A1\0""A2\0""A3\0""A4\0""FAS""Cel", "A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells")
#else
#define LEN_AMPSRC TR("\003", "\005")
#define TR_AMPSRC TR("---""A1\0""A2\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""FAS\0 ""Cells")
#endif
#define LEN_VARIOSRC "\004"
#if defined(TELEMETRY_FRSKY_SPORT)
@ -394,13 +350,8 @@
#define TR_VARIOSRC "Alt\0""Alt+""VSpd""A1\0 ""A2\0"
#endif
#if defined(CPUARM)
#define LEN_VTELEMSCREENTYPE "\010"
#define TR_VTELEMSCREENTYPE "Nic\0 ""Hodnota ""Ukazatel""Skript\0"
#else
#define LEN_VTELEMSCREENTYPE "\010"
#define TR_VTELEMSCREENTYPE "Hodnota ""Ukazatel"
#endif
#define LEN_GPSFORMAT "\004"
#define TR_GPSFORMAT "DMS\0""NMEA"
@ -443,18 +394,12 @@
#define LEN_INPUTNAMES "\004"
#define TR_INPUTNAMES "Sme\0""Vys\0""Pln\0""Kri\0"
#if defined(CPUARM)
#define TR_STICKS_VSRCRAW "\307Smě""\307Výš""\307Pln""\307Kři"
#else
#define TR_STICKS_VSRCRAW "Směr""Výšk""Plyn""Křid"
#endif
#if defined(PCBHORUS)
#define TR_TRIMS_VSRCRAW "\313Smě""\313Výš""\313Pln""\313Kři""\313T5\0""\313T6\0"
#elif defined(CPUARM)
#define TR_TRIMS_VSRCRAW "\313Smě""\313Výš""\313Pln""\313Kři"
#else
#define TR_TRIMS_VSRCRAW "TrmS""TrmV""TrmP""TrmK"
#define TR_TRIMS_VSRCRAW "\313Smě""\313Výš""\313Pln""\313Kři"
#endif
#if defined(PCBX12S)
@ -485,11 +430,7 @@
#define TR_9X_3POS_SWITCHES "ID0""ID1""ID2"
#endif
#if defined(CPUARM)
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12""L13""L14""L15""L16""L17""L18""L19""L20""L21""L22""L23""L24""L25""L26""L27""L28""L29""L30""L31""L32"
#else
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12"
#endif
#if defined(PCBHORUS)
#define TR_TRIMS_SWITCHES "\313Sl""\313Sp""\313Vd""\313Vn""\313Pd""\313Pn""\313Kl""\313Kp""\3135d""\3135n""\3136d""\3136n"
@ -500,9 +441,6 @@
#if defined(PCBSKY9X)
#define TR_ROTARY_ENCODERS "REa\0"
#define TR_ROTENC_SWITCHES "REa"
#elif defined(PCBGRUVIN9X) || defined(PCBMEGA2560)
#define TR_ROTARY_ENCODERS "REa\0""REb\0"
#define TR_ROTENC_SWITCHES "REa""REb"
#else
#define TR_ROTARY_ENCODERS
#define TR_ROTENC_SWITCHES
@ -529,13 +467,8 @@
#define TR_CYC_VSRCRAW "[C1]""[C2]""[C3]"
#endif
#if defined(CPUARM)
#define TR_RESERVE_VSRCRAW "[--]"
#define TR_EXTRA_VSRCRAW "Bat.""Čas\0""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" "Bat." "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
@ -553,14 +486,6 @@
#define LEN_VFAILSAFE "\012"
#define TR_VFAILSAFE "Nenastaven""Držet\0 ""Vlastní\0 ""Bez pulzů\0""Přijímač\0"
#if defined(TELEMETRY_MAVLINK)
#define LEN_MAVLINK_BAUDS "\006"
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""58798 ""76800"
#define LEN_MAVLINK_AC_MODES "\011"
#define TR_MAVLINK_AC_MODES "Stabilize""Acro ""Alt Hold ""Auto ""Guided ""Loiter ""RTL ""Circle ""Pos Hold ""Land ""OF Loiter""Toy A ""Toy M ""INVALID "
#define LEN_MAVLINK_AP_MODES "\015"
#define TR_MAVLINK_AP_MODES "Manual ""Circle ""Stabilize ""Training ""Fly by Wire A""Fly by Wire A""Auto ""RTL ""Loiter ""Guided ""Initialising ""INVALID "
#endif
#define LEN_VSENSORTYPES "\011"
#define TR_VSENSORTYPES "Vlastní\0 ""Vypočtený"
@ -625,11 +550,7 @@
#define TR_PHASENAME "Název"
#define TR_MIXNAME "Název"
#define TR_INPUTNAME "Název"
#if defined(CPUARM)
#define TR_EXPONAME "Popis"
#else
#define TR_EXPONAME "Název"
#endif
#define TR_BITMAP "Obrázek"
#define TR_TIMER "Stopky"
#define TR_ELIMITS TR("Limit +25%", "Kanál +/- 125%")
@ -644,13 +565,9 @@
#define TR_OUTPUT_TYPE INDENT "Output"
#endif
#define TR_PROTO INDENT "Protokol"
#if defined(CPUARM)
#define TR_PPMFRAME INDENT "PPM frame"
#define TR_REFRESHRATE TR(INDENT "Refresh", INDENT "Refresh rate")
#define STR_WARN_BATTVOLTAGE TR(INDENT "Output is VBAT: ", INDENT "Warning: output level is VBAT: ")
#else
#define TR_PPMFRAME "PPM frame"
#endif
#define TR_MS "ms"
#define TR_SWITCH "Spínač"
#define TR_TRIMS "Trimy"
@ -773,13 +690,8 @@
#define TR_TMR1LATMINUS "Tmr1Lat min\037\124us"
#define TR_TMR1JITTERUS "Tmr1 Jitter\037\124us"
#if defined(CPUARM)
#define TR_TMIXMAXMS "Tmix max"
#define TR_FREESTACKMINB "Free Stack"
#else
#define TR_TMIXMAXMS "Tmix max\037\124ms"
#define TR_FREESTACKMINB "Free Stack\037\124b"
#endif
#define TR_MENUTORESET CENTER TR_ENTER" >> Reset"
#define TR_PPM_TRAINER "TR"
@ -824,11 +736,7 @@
#define TR_MENULIMITS "SERVA"
#if defined(CPUARM)
#define TR_MENUINPUTS "VSTUPY"
#else
#define TR_MENUINPUTS "DR/EXPO"
#endif
#define TR_MENUCURVES "KŘIVKY"
#define TR_MENUCURVE "\002K"
@ -847,13 +755,8 @@
#define TR_MONITOR_CHANNELS4 "MONITOR KANÁLŮ 25/32"
#define TR_MONITOR_OUTPUT_DESC "Výstupy"
#define TR_MONITOR_MIXER_DESC "Mixy"
#if defined(CPUARM)
#define TR_RECEIVER_NUM TR(INDENT "RX číslo", INDENT "Číslo přijímače")
#define TR_RECEIVER INDENT "Přijímač"
#else
#define TR_RECEIVER_NUM "RX číslo"
#define TR_RECEIVER "RxNum"
#endif
#define TR_MULTI_RFTUNE TR(INDENT "Freq tune",INDENT "RF Freq. fine tune")
#define TR_MULTI_TELEMETRY "Telemetry"
#define TR_MULTI_VIDFREQ TR(INDENT "Vid. freq.", INDENT "Video frequency")
@ -1110,31 +1013,6 @@
#define TR_CONFIRMRESET "Smazat modely a nastavení?"
#define TR_TO_MANY_LUA_SCRIPTS "Příliš mnoho skriptů!"
#if defined(TELEMETRY_MAVLINK)
#define TR_MAVLINK_RC_RSSI_SCALE_LABEL "Max RSSI"
#define TR_MAVLINK_PC_RSSI_EN_LABEL "PC RSSI EN"
#define TR_MAVMENUSETUP_TITLE "Mavlink Setup"
#define TR_MAVLINK_BAUD_LABEL "Baudrate"
#define TR_MAVLINK_INFOS "INFOS"
#define TR_MAVLINK_MODE "MODE"
#define TR_MAVLINK_CUR_MODE "Current Mode"
#define TR_MAVLINK_ARMED "Armed"
#define TR_MAVLINK_BAT_MENU_TITLE "BAT RSSI"
#define TR_MAVLINK_BATTERY_LABEL "Flight Battery status"
#define TR_MAVLINK_RC_RSSI_LABEL "RC RSSI"
#define TR_MAVLINK_PC_RSSI_LABEL "PC RSSI"
#define TR_MAVLINK_NAV_MENU_TITLE "NAV"
#define TR_MAVLINK_COURSE "Course"
#define TR_MAVLINK_HEADING "Heading"
#define TR_MAVLINK_BEARING "Bearing"
#define TR_MAVLINK_ALTITUDE "Altitude"
#define TR_MAVLINK_GPS "GPS"
#define TR_MAVLINK_NO_FIX "NO Fix"
#define TR_MAVLINK_SAT "SAT"
#define TR_MAVLINK_HDOP "HDOP"
#define TR_MAVLINK_LAT "LAT"
#define TR_MAVLINK_LON "LON"
#endif
// Horus and Taranis column headers

View file

@ -144,8 +144,6 @@
#define TR_RETA123 "SHGQ123LR"
#elif defined(PCBSKY9X)
#define TR_RETA123 "SHGQ123a"
#elif defined(CPUM2560)
#define TR_RETA123 "SHGQ123ab"
#else
#define TR_RETA123 "SHGQ123"
#endif
@ -174,11 +172,7 @@
#define TR_IRPROTOS
#endif
#if defined(CPUARM)
#define TR_XPPM
#else
#define TR_XPPM "PPM16\0""PPMsim"
#endif
#define TR_VPROTOS "PPM\0 " TR_XPPM TR_PXX TR_DSM2 TR_IRPROTOS
@ -215,27 +209,14 @@
#else
#define TR_CSWTIMER "Takt\0" // TIM = Takt = Taktgenerator
#define TR_CSWSTICKY "SRFF\0" // Sticky = RS-Flip-Flop
#if defined(CPUARM)
#define TR_CSWRANGE "Rnge\0" // Range= Bereichsabfrage von bis
#define TR_CSWSTAY "Puls\0" // Edge = einstellbarer Impuls
#else
#define TR_CSWRANGE
#define TR_CSWSTAY
#endif
#endif
#if defined(CPUARM)
#define TR_CSWEQUAL "a=x\0 "
#else
#define TR_CSWEQUAL
#endif
#define LEN_VCSWFUNC "\005"
#if defined(CPUARM)
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""Δ}x\0 ""|Δ|}x" TR_CSWTIMER TR_CSWSTICKY
#else
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""^}x\0 ""|^|}x" TR_CSWTIMER TR_CSWSTICKY
#endif
#define LEN_VFSWFUNC "\012"
@ -313,13 +294,7 @@
#define TR_SF_RESERVE "[Reserve]\0"
#if defined(CPUARM)
#define TR_VFSWFUNC TR_SF_SAFETY "Lehrer \0 ""Inst. Trim""Rücksetz.\0""Setze \0 " TR_ADJUST_GVAR "Lautstr.\0 " "SetFailsfe" "RangeCheck" "ModuleBind" TR_SOUND TR_PLAY_TRACK TR_PLAY_VALUE TR_SF_RESERVE TR_SF_PLAY_SCRIPT TR_SF_RESERVE TR_SF_BG_MUSIC TR_VVARIO TR_HAPTIC TR_SDCLOGS "LCD Licht\0" TR_SF_SCREENSHOT TR_SF_TEST
#elif defined(PCBGRUVIN9X)
#define TR_VFSWFUNC TR_SF_SAFETY "Lehrer \0 ""Inst. Trim""Rücksetz.\0" TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC TR_SDCLOGS "LCD Licht\0" TR_SF_TEST
#else
#define TR_VFSWFUNC TR_SF_SAFETY "Lehrer \0 ""Inst. Trim""Rücksetz.\0" TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC "LCD Licht\0" TR_SF_TEST
#endif
#define LEN_VFSWRESET TR("\004", "\011")
@ -339,10 +314,8 @@
#if LCD_W >= 212
#define TR_FSW_RESET_TIMERS "Timer 1\0 ""Timer 2\0 ""Timer 3\0 "
#elif defined(CPUARM)
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#else
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2"
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#endif
#define TR_VFSWRESET TR(TR_FSW_RESET_TIMERS "All\0" TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC, TR_FSW_RESET_TIMERS "All\0 " TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC)
@ -352,21 +325,12 @@
#define LEN_VTELEMCHNS "\004"
#if defined(CPUARM)
#define TR_TELEM_RESERVE TR("[--]", "[---]")
#define TR_TELEM_TIME TR("Zeit", "Zeit\0")
#define TR_RAS 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_RAS
#define TR_RX_BATT
#define TR_A3_A4
#define TR_A3_A4_MIN
#endif
#define TR_ASPD_MAX TR("ASp+", "ASpd+")
@ -376,33 +340,17 @@
#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
#define LENGTH_UNIT_IMP "ft\0"
#define SPEED_UNIT_IMP "mph"
#define LENGTH_UNIT_METR "m\0 "
#define SPEED_UNIT_METR "kmh"
#if defined(CPUARM)
#define LEN_VUNITSSYSTEM TR("\006", "\012")
#define TR_VUNITSSYSTEM TR("Metrik""Imper.", "Metrisch\0 ""Imperial\0 ")
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "-\0 ""V\0 ""A\0 ""mA\0""kts""m/s""f/s""kmh""mph""m\0 ""ft\0""@C\0""@F\0""%\0 ""mAh""W\0 ""mW\0""dB\0""rpm""g\0 ""@\0 ""rad""ml\0""fOz"
#else
#if defined(IMPERIAL_UNITS)
#define LENGTH_UNIT LENGTH_UNIT_IMP
#define SPEED_UNIT SPEED_UNIT_IMP
#else
#define LENGTH_UNIT LENGTH_UNIT_METR
#define SPEED_UNIT SPEED_UNIT_METR
#endif
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "V\0 ""A\0 ""m/s""-\0 " SPEED_UNIT LENGTH_UNIT "@\0 ""%\0 ""mA\0""mAh""W\0 "
#endif
#define STR_V (STR_VTELEMUNIT+1)
#define STR_A (STR_VTELEMUNIT+4)
@ -416,15 +364,10 @@
#define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "Kein\0 ""Hub\0 ""WSHHigh"
#if defined(CPUARM)
#define LEN_AMPSRC TR("\003", "\005")
#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")
#define LEN_VOLTSRC TR("\003", "\005")
#define TR_VOLTSRC TR("A1\0""A2\0""A3\0""A4\0""FAS""Cel", "A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells")
#else
#define LEN_AMPSRC TR("\003", "\005")
#define TR_AMPSRC TR("---""A1\0""A2\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""FAS\0 ""Cells")
#endif
#define LEN_VARIOSRC "\004"
#if defined(TELEMETRY_FRSKY_SPORT)
@ -433,13 +376,8 @@
#define TR_VARIOSRC "Alt\0""Alt+""Vspd""A1\0 ""A2\0 "
#endif
#if defined(CPUARM)
#define LEN_VTELEMSCREENTYPE "\007"
#define TR_VTELEMSCREENTYPE " None "" Werte "" Balken"" Script"
#else
#define LEN_VTELEMSCREENTYPE "\007"
#define TR_VTELEMSCREENTYPE " Werte "" Balken"
#endif
#define LEN_GPSFORMAT "\004"
#define TR_GPSFORMAT "GMS\0""NMEA" //Koordinatenanzeige
@ -511,11 +449,7 @@
#define TR_9X_3POS_SWITCHES "ID0""ID1""ID2"
#endif
#if defined(CPUARM)
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12""L13""L14""L15""L16""L17""L18""L19""L20""L21""L22""L23""L24""L25""L26""L27""L28""L29""L30""L31""L32"
#else
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12"
#endif
#if defined(PCBHORUS)
#define TR_TRIMS_SWITCHES "\313Rl""\313Rr""\313Ed""\313Eu""\313Td""\313Tu""\313Al""\313Ar""\3135d""\3135u""\3136d""\3136u"
@ -526,9 +460,6 @@
#if defined(PCBSKY9X)
#define TR_ROTARY_ENCODERS "DGa\0"
#define TR_ROTENC_SWITCHES "DGa"
#elif defined(PCBGRUVIN9X) || defined(PCBMEGA2560)
#define TR_ROTARY_ENCODERS "DGa\0""DGb\0"
#define TR_ROTENC_SWITCHES "DGa""DGb"
#else
#define TR_ROTARY_ENCODERS
#define TR_ROTENC_SWITCHES
@ -555,13 +486,8 @@
#define TR_CYC_VSRCRAW "[C1]""[C2]""[C3]"
#endif
#if defined(CPUARM)
#define TR_RESERVE_VSRCRAW "[--]"
#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""Akku" TR_TELEM_TIME TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_TIMERS TR_RAS "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""Zeit"
#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
@ -579,14 +505,6 @@
#define LEN_VFAILSAFE "\015" // "\013" original
#define TR_VFAILSAFE "Kein Failsafe""Halte Pos.\0 ""Kanäle\0 ""Kein Signal\0 ""Empfänger\0 "
#if defined(TELEMETRY_MAVLINK)
#define LEN_MAVLINK_BAUDS "\006"
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""58798 ""76800"
#define LEN_MAVLINK_AC_MODES "\011"
#define TR_MAVLINK_AC_MODES "Stabilize""Acro ""Alt Hold ""Auto ""Guided ""Loiter ""RTL ""Circle ""Pos Hold ""Land ""OF Loiter""Toy A ""Toy M ""INVALID "
#define LEN_MAVLINK_AP_MODES "\015"
#define TR_MAVLINK_AP_MODES "Manual ""Circle ""Stabilize ""Training ""Fly by Wire A""Fly by Wire A""Auto ""RTL ""Loiter ""Guided ""Initialising ""INVALID "
#endif
#define LEN_VSENSORTYPES "\012"
#define TR_VSENSORTYPES "Sensor\0 ""Berechnung"
@ -641,11 +559,7 @@
#define TR_PHASENAME "Phase-Name"
#define TR_MIXNAME "Mix-Name"
#define TR_INPUTNAME "Input"
#if defined(CPUARM)
#define TR_EXPONAME "Info"
#else
#define TR_EXPONAME "Info" // Expo Name
#endif
#define TR_BITMAP "Modellfoto"
#define TR_TIMER TR("Timer", "Timer ") // für Timer1 Timer2 Timer3
#define TR_ELIMITS TR("Erw. Limit", "Erw. Wege auf 150%")
@ -660,13 +574,9 @@
#define TR_OUTPUT_TYPE INDENT "Output"
#endif
#define TR_PROTO TR(INDENT "Protok.", INDENT "Protokoll")
#if defined(CPUARM)
#define TR_PPMFRAME INDENT "PPM frame"
#define TR_REFRESHRATE TR(INDENT "Refresh", INDENT "Refresh rate")
#define STR_WARN_BATTVOLTAGE TR(INDENT "Output is VBAT: ", INDENT "Warning: output level is VBAT: ")
#else
#define TR_PPMFRAME "PPM frame"
#endif
#define TR_MS "ms"
#define TR_SWITCH TR("Schalt.", "Schalter")
#define TR_TRIMS "Trims"
@ -791,13 +701,8 @@
#define TR_TMR1LATMINUS "Tmr1Lat min\037\124us"
#define TR_TMR1JITTERUS "Tmr1 Jitter\037\124us"
#if defined(CPUARM)
#define TR_TMIXMAXMS "Tmix max"
#define TR_FREESTACKMINB "Freier Stack"
#else
#define TR_TMIXMAXMS "Tmix max\037\124ms"
#define TR_FREESTACKMINB "Freier Stack\037\124b"
#endif
#define TR_MENUTORESET CENTER TR_ENTER " für Reset"
#define TR_PPM_TRAINER "TR"
@ -840,13 +745,8 @@
#define TR_MENUFLIGHTMODES "FLUGPHASEN"
#define TR_MENUHELISETUP TR("HELI TS-Mischer", "HELI TS-Mischer CYC1-3")
#if defined(CPUARM)
#define TR_MENUINPUTS "INPUTS"
#define TR_MENULIMITS "SERVOS" //"AUSGABEN" oder "Servos"
#else
#define TR_MENUINPUTS "KNÜPPEL"
#define TR_MENULIMITS "SERVOS"
#endif
#define TR_MENUCURVES "KURVEN"
#define TR_MENUCURVE "KURVE"
#define TR_MENULOGICALSWITCH "LOGIKSCHALTER"
@ -864,13 +764,8 @@
#define TR_MONITOR_SWITCHES "LOGIK SCHALTER MONITOR"
#define TR_MONITOR_OUTPUT_DESC "Kanäle"
#define TR_MONITOR_MIXER_DESC "Mischer"
#if defined(CPUARM)
#define TR_RECEIVER_NUM TR(INDENT "Empf Nr.", INDENT "Empfänger Nummer")
#define TR_RECEIVER INDENT "Receiver"
#else
#define TR_RECEIVER_NUM "Empf Nr."
#define TR_RECEIVER "Empf Nr."
#endif
#define TR_MULTI_RFTUNE TR(INDENT "RF Freq.", INDENT "RF Freq. Feintuning")
#define TR_MULTI_TELEMETRY "Telemetry"
#define TR_MULTI_VIDFREQ TR(INDENT "Vid. Freq.", INDENT "Video Frequenz")
@ -1122,31 +1017,6 @@
#define TR_CONFIRMRESET TR("Alles löschen? ","ALLE Modelle+Einst. löschen?")
#define TR_TO_MANY_LUA_SCRIPTS "Zu viele Lua-Skripte!"
#if defined(TELEMETRY_MAVLINK)
#define TR_MAVLINK_RC_RSSI_SCALE_LABEL "Max RSSI"
#define TR_MAVLINK_PC_RSSI_EN_LABEL "PC RSSI EN"
#define TR_MAVMENUSETUP_TITLE "Mavlink Setup"
#define TR_MAVLINK_BAUD_LABEL "Baudrate"
#define TR_MAVLINK_INFOS "INFOS"
#define TR_MAVLINK_MODE "MODE"
#define TR_MAVLINK_CUR_MODE "Current Mode"
#define TR_MAVLINK_ARMED "Armed"
#define TR_MAVLINK_BAT_MENU_TITLE "BAT RSSI"
#define TR_MAVLINK_BATTERY_LABEL "Flugakku-Status"
#define TR_MAVLINK_RC_RSSI_LABEL "RC RSSI"
#define TR_MAVLINK_PC_RSSI_LABEL "PC RSSI"
#define TR_MAVLINK_NAV_MENU_TITLE "NAV"
#define TR_MAVLINK_COURSE "Course"
#define TR_MAVLINK_HEADING "Heading"
#define TR_MAVLINK_BEARING "Bearing"
#define TR_MAVLINK_ALTITUDE "Altitude"
#define TR_MAVLINK_GPS "GPS"
#define TR_MAVLINK_NO_FIX "NO Fix"
#define TR_MAVLINK_SAT "SAT"
#define TR_MAVLINK_HDOP "HDOP"
#define TR_MAVLINK_LAT "LAT"
#define TR_MAVLINK_LON "LON"
#endif
// Horus and Taranis specific column headers
#define TR_PHASES_HEADERS_NAME "Name "

View file

@ -143,8 +143,6 @@
#define TR_RETA123 "RETA123LR"
#elif defined(PCBSKY9X)
#define TR_RETA123 "RETA123a"
#elif defined(CPUM2560)
#define TR_RETA123 "RETA123ab"
#else
#define TR_RETA123 "RETA123"
#endif
@ -174,11 +172,7 @@
#define TR_IRPROTOS
#endif
#if defined(CPUARM)
#define TR_XPPM
#else
#define TR_XPPM "PPM16\0""PPMsim"
#endif
#define TR_VPROTOS "PPM\0 " TR_XPPM TR_PXX TR_DSM2 TR_IRPROTOS
@ -215,27 +209,14 @@
#else
#define TR_CSWTIMER "Tim\0 "
#define TR_CSWSTICKY "Stky\0"
#if defined(CPUARM)
#define TR_CSWRANGE "Rnge\0"
#define TR_CSWSTAY "Edge\0"
#else
#define TR_CSWRANGE
#define TR_CSWSTAY
#endif
#endif
#if defined(CPUARM)
#define TR_CSWEQUAL "a=x\0 "
#else
#define TR_CSWEQUAL
#endif
#define LEN_VCSWFUNC "\005"
#if defined(CPUARM)
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""Δ}x\0 ""|Δ|}x" TR_CSWTIMER TR_CSWSTICKY
#else
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""^}x\0 ""|^|}x" TR_CSWTIMER TR_CSWSTICKY
#endif
#define LEN_VFSWFUNC "\012"
@ -313,13 +294,7 @@
#define TR_SF_RESERVE "[reserve]\0"
#if defined(CPUARM)
#define TR_VFSWFUNC TR_SF_SAFETY "Trainer\0 ""Inst. Trim""Reset\0 ""Set \0 " TR_ADJUST_GVAR "Volume\0 " "SetFailsfe" "RangeCheck" "ModuleBind" TR_SOUND TR_PLAY_TRACK TR_PLAY_VALUE TR_SF_RESERVE TR_SF_PLAY_SCRIPT TR_SF_RESERVE TR_SF_BG_MUSIC TR_VVARIO TR_HAPTIC TR_SDCLOGS "Backlight\0" TR_SF_SCREENSHOT TR_SF_TEST
#elif defined(PCBGRUVIN9X)
#define TR_VFSWFUNC TR_SF_SAFETY "Trainer\0 ""Inst. Trim""Reset\0 " TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC TR_SDCLOGS "Backlight\0" TR_SF_TEST
#else
#define TR_VFSWFUNC TR_SF_SAFETY "Trainer\0 ""Inst. Trim""Reset\0 " TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC "Backlight\0" TR_SF_TEST
#endif
#define LEN_VFSWRESET TR("\004", "\011")
@ -339,10 +314,8 @@
#if LCD_W >= 212
#define TR_FSW_RESET_TIMERS "Timer 1\0 ""Timer 2\0 ""Timer 3\0 "
#elif defined(CPUARM)
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#else
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2"
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#endif
#define TR_VFSWRESET TR(TR_FSW_RESET_TIMERS "All\0" TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC, TR_FSW_RESET_TIMERS "Flight\0 " TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC)
@ -357,22 +330,10 @@
#define LENGTH_UNIT_METR "m\0 "
#define SPEED_UNIT_METR "kmh"
#if defined(CPUARM)
#define LEN_VUNITSSYSTEM TR("\006", "\010")
#define TR_VUNITSSYSTEM TR("Metric""Imper.", "Metric\0 ""Imperial")
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "-\0 ""V\0 ""A\0 ""mA\0""kts""m/s""f/s""kmh""mph""m\0 ""ft\0""@C\0""@F\0""%\0 ""mAh""W\0 ""mW\0""dB\0""rpm""g\0 ""@\0 ""rad""ml\0""fOz"
#else
#if defined(IMPERIAL_UNITS)
#define LENGTH_UNIT LENGTH_UNIT_IMP
#define SPEED_UNIT SPEED_UNIT_IMP
#else
#define LENGTH_UNIT LENGTH_UNIT_METR
#define SPEED_UNIT SPEED_UNIT_METR
#endif
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "V\0 ""A\0 ""m/s""-\0 " SPEED_UNIT LENGTH_UNIT "@\0 ""%\0 ""mA\0""mAh""W\0 "
#endif
#define STR_V (STR_VTELEMUNIT+1)
#define STR_A (STR_VTELEMUNIT+4)
@ -386,15 +347,10 @@
#define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "None\0 ""Hub\0 ""WSHHigh"
#if defined(CPUARM)
#define LEN_AMPSRC TR("\003", "\005")
#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")
#define LEN_VOLTSRC TR("\003", "\005")
#define TR_VOLTSRC TR("A1\0""A2\0""A3\0""A4\0""FAS""Cel", "A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells")
#else
#define LEN_AMPSRC TR("\003", "\005")
#define TR_AMPSRC TR("---""A1\0""A2\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""FAS\0 ""Cells")
#endif
#define LEN_VARIOSRC "\004"
#if defined(TELEMETRY_FRSKY_SPORT)
@ -403,13 +359,8 @@
#define TR_VARIOSRC "Alt\0""Alt+""VSpd""A1\0 ""A2\0"
#endif
#if defined(CPUARM)
#define LEN_VTELEMSCREENTYPE "\006"
#define TR_VTELEMSCREENTYPE "None\0 ""Nums\0 ""Bars\0 ""Script"
#else
#define LEN_VTELEMSCREENTYPE "\004"
#define TR_VTELEMSCREENTYPE "Nums""Bars"
#endif
#define LEN_GPSFORMAT "\004"
#define TR_GPSFORMAT "DMS\0""NMEA"
@ -452,18 +403,12 @@
#define LEN_VSWITCHES "\003"
#define LEN_VSRCRAW "\004"
#if defined(CPUARM)
#define TR_STICKS_VSRCRAW "\307Rud""\307Ele""\307Thr""\307Ail"
#else
#define TR_STICKS_VSRCRAW "Rud\0""Ele\0""Thr\0""Ail\0"
#endif
#if defined(PCBHORUS)
#define TR_TRIMS_VSRCRAW "\313Rud""\313Ele""\313Thr""\313Ail""\313T5\0""\313T6\0"
#elif defined(CPUARM)
#define TR_TRIMS_VSRCRAW "\313Rud""\313Ele""\313Thr""\313Ail"
#else
#define TR_TRIMS_VSRCRAW "TrmR""TrmE""TrmT""TrmA"
#define TR_TRIMS_VSRCRAW "\313Rud""\313Ele""\313Thr""\313Ail"
#endif
#if defined(PCBX12S)
@ -494,11 +439,7 @@
#define TR_9X_3POS_SWITCHES "ID0""ID1""ID2"
#endif
#if defined(CPUARM)
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12""L13""L14""L15""L16""L17""L18""L19""L20""L21""L22""L23""L24""L25""L26""L27""L28""L29""L30""L31""L32"
#else
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12"
#endif
#if defined(PCBHORUS)
#define TR_TRIMS_SWITCHES "\313Rl""\313Rr""\313Ed""\313Eu""\313Td""\313Tu""\313Al""\313Ar""\3135d""\3135u""\3136d""\3136u"
@ -509,9 +450,6 @@
#if defined(PCBSKY9X)
#define TR_ROTARY_ENCODERS "REa\0"
#define TR_ROTENC_SWITCHES "REa"
#elif defined(PCBGRUVIN9X) || defined(PCBMEGA2560)
#define TR_ROTARY_ENCODERS "REa\0""REb\0"
#define TR_ROTENC_SWITCHES "REa""REb"
#else
#define TR_ROTARY_ENCODERS
#define TR_ROTENC_SWITCHES
@ -538,13 +476,8 @@
#define TR_CYC_VSRCRAW "[C1]""[C2]""[C3]"
#endif
#if defined(CPUARM)
#define TR_RESERVE_VSRCRAW "[--]"
#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
@ -562,14 +495,6 @@
#define LEN_VFAILSAFE "\011"
#define TR_VFAILSAFE "Not set\0 ""Hold\0 ""Custom\0 ""No pulses""Receiver\0"
#if defined(TELEMETRY_MAVLINK)
#define LEN_MAVLINK_BAUDS "\006"
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""58798 ""76800"
#define LEN_MAVLINK_AC_MODES "\011"
#define TR_MAVLINK_AC_MODES "Stabilize""Acro ""Alt Hold ""Auto ""Guided ""Loiter ""RTL ""Circle ""Pos Hold ""Land ""OF Loiter""Toy A ""Toy M ""INVALID "
#define LEN_MAVLINK_AP_MODES "\015"
#define TR_MAVLINK_AP_MODES "Manual ""Circle ""Stabilize ""Training ""Fly by Wire A""Fly by Wire A""Auto ""RTL ""Loiter ""Guided ""Initialising ""INVALID "
#endif
#define LEN_VSENSORTYPES "\012"
#define TR_VSENSORTYPES "Custom\0 ""Calculated"
@ -648,13 +573,9 @@
#define TR_OUTPUT_TYPE INDENT "Output"
#endif
#define TR_PROTO TR(INDENT "Proto", INDENT "Protocol")
#if defined(CPUARM)
#define TR_PPMFRAME INDENT "PPM frame"
#define TR_REFRESHRATE TR(INDENT "Refresh", INDENT "Refresh rate")
#define STR_WARN_BATTVOLTAGE TR(INDENT "Output is VBAT: ", INDENT "Warning: output level is VBAT: ")
#else
#define TR_PPMFRAME "PPM frame"
#endif
#define TR_MS "ms"
#define TR_SWITCH "Switch"
#define TR_TRIMS "Trims"
@ -779,13 +700,8 @@
#define TR_TMR1LATMINUS "Tmr1Lat min\037\124us"
#define TR_TMR1JITTERUS "Tmr1 Jitter\037\124us"
#if defined(CPUARM)
#define TR_TMIXMAXMS "Tmix max"
#define TR_FREESTACKMINB "Free Stack"
#else
#define TR_TMIXMAXMS "Tmix max\037\124ms"
#define TR_FREESTACKMINB "Free Stack\037\124b"
#endif
#define TR_MENUTORESET CENTER TR_ENTER " to reset"
#define TR_PPM_TRAINER "TR"
@ -828,13 +744,8 @@
#define TR_MENUFLIGHTMODE "FLIGHT MODE"
#define TR_MENUHELISETUP "HELI SETUP"
#if defined(CPUARM)
#define TR_MENUINPUTS "INPUTS"
#define TR_MENULIMITS "OUTPUTS"
#else
#define TR_MENUINPUTS "STICKS"
#define TR_MENULIMITS "SERVOS"
#endif
#define TR_MENUCURVES "CURVES"
#define TR_MENUCURVE "CURVE"
#define TR_MENULOGICALSWITCH "LOGICAL SWITCH"
@ -852,13 +763,8 @@
#define TR_MONITOR_SWITCHES "LOGICAL SWITCHES MONITOR"
#define TR_MONITOR_OUTPUT_DESC "Outputs"
#define TR_MONITOR_MIXER_DESC "Mixers"
#if defined(CPUARM)
#define TR_RECEIVER_NUM TR(INDENT "RxNum", INDENT "Receiver No.")
#define TR_RECEIVER INDENT "Receiver"
#else
#define TR_RECEIVER_NUM "RxNum"
#define TR_RECEIVER "RxNum"
#endif
#define TR_MULTI_RFTUNE TR(INDENT "Freq tune",INDENT "RF Freq. fine tune")
#define TR_MULTI_TELEMETRY "Telemetry"
#define TR_MULTI_VIDFREQ TR(INDENT "Vid. freq.", INDENT "Video frequency")
@ -1122,31 +1028,6 @@
#define TR_CONFIRMRESET TR("Erase ALL", "Erase ALL models and settings?")
#define TR_TO_MANY_LUA_SCRIPTS "Too many Lua scripts!"
#if defined(TELEMETRY_MAVLINK)
#define TR_MAVLINK_RC_RSSI_SCALE_LABEL "Max RSSI"
#define TR_MAVLINK_PC_RSSI_EN_LABEL "PC RSSI EN"
#define TR_MAVMENUSETUP_TITLE "Mavlink setup"
#define TR_MAVLINK_BAUD_LABEL "Baudrate"
#define TR_MAVLINK_INFOS "INFOS"
#define TR_MAVLINK_MODE "MODE"
#define TR_MAVLINK_CUR_MODE "Current mode"
#define TR_MAVLINK_ARMED "Armed"
#define TR_MAVLINK_BAT_MENU_TITLE "BAT RSSI"
#define TR_MAVLINK_BATTERY_LABEL "Flight battery status"
#define TR_MAVLINK_RC_RSSI_LABEL "RC RSSI"
#define TR_MAVLINK_PC_RSSI_LABEL "PC RSSI"
#define TR_MAVLINK_NAV_MENU_TITLE "NAV"
#define TR_MAVLINK_COURSE "Course"
#define TR_MAVLINK_HEADING "Heading"
#define TR_MAVLINK_BEARING "Bearing"
#define TR_MAVLINK_ALTITUDE "Altitude"
#define TR_MAVLINK_GPS "GPS"
#define TR_MAVLINK_NO_FIX "NO Fix"
#define TR_MAVLINK_SAT "SAT"
#define TR_MAVLINK_HDOP "HDOP"
#define TR_MAVLINK_LAT "LAT"
#define TR_MAVLINK_LON "LON"
#endif
// Horus and Taranis column headers
#define TR_PHASES_HEADERS_NAME "Name"

View file

@ -139,8 +139,6 @@
#define TR_RETA123 "RETA123LR"
#elif defined(PCBSKY9X)
#define TR_RETA123 "RETA123a"
#elif defined(CPUM2560)
#define TR_RETA123 "RETA123ab"
#else
#define TR_RETA123 "RETA123"
#endif
@ -169,11 +167,7 @@
#define TR_IRPROTOS
#endif
#if defined(CPUARM)
#define TR_XPPM
#else
#define TR_XPPM "PPM16\0""PPMsim"
#endif
#define TR_VPROTOS "PPM\0 " TR_XPPM TR_PXX TR_DSM2 TR_IRPROTOS
@ -210,27 +204,14 @@
#else
#define TR_CSWTIMER "Tim\0 "
#define TR_CSWSTICKY "Glue\0"
#if defined(CPUARM)
#define TR_CSWRANGE "Rnge\0"
#define TR_CSWSTAY "Edge\0"
#else
#define TR_CSWRANGE
#define TR_CSWSTAY
#endif
#endif
#if defined(CPUARM)
#define TR_CSWEQUAL "a=x\0 "
#else
#define TR_CSWEQUAL
#endif
#define LEN_VCSWFUNC "\005"
#if defined(CPUARM)
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""Δ}x\0 ""|Δ|}x" TR_CSWTIMER TR_CSWSTICKY
#else
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""^}x\0 ""|^|}x" TR_CSWTIMER TR_CSWSTICKY
#endif
#define LEN_VFSWFUNC "\012"
@ -306,13 +287,7 @@
#define TR_SF_RESERVE "[reserve]\0"
#if defined(CPUARM)
#define TR_VFSWFUNC TR_SF_SAFETY "Aprendiz\0 ""Inst. Trim""Reset\0 ""Set \0 " TR_ADJUST_GVAR "Volumen\0 " "SetFailsfe" "RangeCheck" "ModuleBind" TR_SOUND TR_PLAY_TRACK TR_PLAY_VALUE TR_SF_RESERVE TR_SF_PLAY_SCRIPT TR_SF_RESERVE TR_SF_BG_MUSIC TR_VVARIO TR_HAPTIC TR_SDCLOGS "Luz fondo\0" TR_SF_SCREENSHOT TR_SF_TEST
#elif defined(PCBGRUVIN9X)
#define TR_VFSWFUNC TR_SF_SAFETY "Aprendiz\0 ""Inst. Trim""Reset\0 " TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC TR_SDCLOGS "Luz fondo\0" TR_SF_TEST
#else
#define TR_VFSWFUNC TR_SF_SAFETY "Aprendiz\0 ""Inst. Trim""Reset\0 " TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC "Luz fondo\0" TR_SF_TEST
#endif
#define LEN_VFSWRESET TR("\004", "\011")
@ -332,10 +307,8 @@
#if defined(PCBTARANIS)
#define TR_FSW_RESET_TIMERS "Timer 1\0 ""Timer 2\0 ""Timer 3\0 "
#elif defined(CPUARM)
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#else
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2"
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#endif
#define TR_VFSWRESET TR(TR_FSW_RESET_TIMERS "All\0" TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC, TR_FSW_RESET_TIMERS "All\0 " TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC)
@ -345,21 +318,12 @@
#define LEN_VTELEMCHNS "\004"
#if defined(CPUARM)
#define TR_TELEM_RESERVE TR("[--]", "[---]")
#define TR_TELEM_TIME TR("Time", "Time\0")
#define TR_RAS 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_RAS
#define TR_RX_BATT
#define TR_A3_A4
#define TR_A3_A4_MIN
#endif
#define TR_ASPD_MAX TR("ASp+", "ASpd+")
@ -369,33 +333,17 @@
#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
#define LENGTH_UNIT_IMP "ft\0"
#define SPEED_UNIT_IMP "mph"
#define LENGTH_UNIT_METR "m\0 "
#define SPEED_UNIT_METR "kmh"
#if defined(CPUARM)
#define LEN_VUNITSSYSTEM TR("\006", "\010")
#define TR_VUNITSSYSTEM TR("Metric""Imper.", "Metric\0 ""Imperial")
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "-\0 ""V\0 ""A\0 ""mA\0""kts""m/s""f/s""kmh""mph""m\0 ""ft\0""@C\0""@F\0""%\0 ""mAh""W\0 ""mW\0""dB\0""rpm""g\0 ""@\0 ""rad""ml\0""fOz"
#else
#if defined(IMPERIAL_UNITS)
#define LENGTH_UNIT LENGTH_UNIT_IMP
#define SPEED_UNIT SPEED_UNIT_IMP
#else
#define LENGTH_UNIT LENGTH_UNIT_METR
#define SPEED_UNIT SPEED_UNIT_METR
#endif
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "V\0 ""A\0 ""m/s""-\0 " SPEED_UNIT LENGTH_UNIT "@\0 ""%\0 ""mA\0""mAh""W\0 "
#endif
#define STR_V (STR_VTELEMUNIT+1)
#define STR_A (STR_VTELEMUNIT+4)
@ -409,15 +357,10 @@
#define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "Nada\0 ""Hub\0 ""WSHHigh"
#if defined(CPUARM)
#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("A1\0""A2\0""A3\0""A4\0""FAS""Cel", "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"
#if defined(TELEMETRY_FRSKY_SPORT)
@ -491,11 +434,7 @@
#define TR_9X_3POS_SWITCHES "ID0""ID1""ID2"
#endif
#if defined(CPUARM)
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12""L13""L14""L15""L16""L17""L18""L19""L20""L21""L22""L23""L24""L25""L26""L27""L28""L29""L30""L31""L32"
#else
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12"
#endif
#if defined(PCBHORUS)
#define TR_TRIMS_SWITCHES "\313Rl""\313Rr""\313Ed""\313Eu""\313Td""\313Tu""\313Al""\313Ar""\3135d""\3135u""\3136d""\3136u"
@ -506,9 +445,6 @@
#if defined(PCBSKY9X)
#define TR_ROTARY_ENCODERS "REa\0"
#define TR_ROTENC_SWITCHES "REa"
#elif defined(PCBGRUVIN9X) || defined(PCBMEGA2560)
#define TR_ROTARY_ENCODERS "REa\0""REb\0"
#define TR_ROTENC_SWITCHES "REa""REb"
#else
#define TR_ROTARY_ENCODERS
#define TR_ROTENC_SWITCHES
@ -535,13 +471,8 @@
#define TR_CYC_VSRCRAW "[C1]""[C2]""[C3]"
#endif
#if defined(CPUARM)
#define TR_RESERVE_VSRCRAW "[--]"
#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
@ -559,14 +490,6 @@
#define LEN_VFAILSAFE "\011"
#define TR_VFAILSAFE "Not set\0 ""Guardar\0 ""Adaptar\0 ""Sin pulso""Receiver\0"
#if defined(TELEMETRY_MAVLINK)
#define LEN_MAVLINK_BAUDS "\006"
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""58798 ""76800"
#define LEN_MAVLINK_AC_MODES "\011"
#define TR_MAVLINK_AC_MODES "Estabilizar""Acrobat. ""Alt Hold ""Auto ""Guiado ""Loiter ""RTL ""Circulo ""Pos Hold ""Tierra ""OF Loiter""Toy A ""Toy M ""INVALIDO "
#define LEN_MAVLINK_AP_MODES "\015"
#define TR_MAVLINK_AP_MODES "Manual ""Circulo ""Estabilizar ""Entrenamiento""Fly by Wire A""Fly by Wire A""Auto ""RTL ""Loiter ""Guiado ""Inicialisando""INVALID "
#endif
#define LEN_VSENSORTYPES "\012"
#define TR_VSENSORTYPES "Custom\0 ""Calculated"
@ -771,13 +694,8 @@
#define TR_TMR1LATMINUS "Tmr1Lat min\037\124us"
#define TR_TMR1JITTERUS "Tmr1 Jitter\037\124us"
#if defined(CPUARM)
#define TR_TMIXMAXMS "Tmix max"
#define TR_FREESTACKMINB "Free Stack"
#else
#define TR_TMIXMAXMS "Tmix max\037\124ms"
#define TR_FREESTACKMINB "Pila LIbre\037\124b"
#endif
#define TR_MENUTORESET CENTER TR_ENTER "Resetear"
#define TR_PPM_TRAINER "TR"
@ -1101,31 +1019,6 @@
#define TR_CONFIRMRESET "Erase ALL models and settings?"
#define TR_TO_MANY_LUA_SCRIPTS "Too many Lua scripts!"
#if defined(TELEMETRY_MAVLINK)
#define TR_MAVLINK_RC_RSSI_SCALE_LABEL "Max RSSI"
#define TR_MAVLINK_PC_RSSI_EN_LABEL "PC RSSI EN"
#define TR_MAVMENUSETUP_TITLE "Mavlink Setup"
#define TR_MAVLINK_BAUD_LABEL "Baudrate"
#define TR_MAVLINK_INFOS "INFOS"
#define TR_MAVLINK_MODE "MODO"
#define TR_MAVLINK_CUR_MODE "Modo actual"
#define TR_MAVLINK_ARMED "Armad0"
#define TR_MAVLINK_BAT_MENU_TITLE "BAT RSSI"
#define TR_MAVLINK_BATTERY_LABEL "Estado Bateria de vuelo"
#define TR_MAVLINK_RC_RSSI_LABEL "RC RSSI"
#define TR_MAVLINK_PC_RSSI_LABEL "PC RSSI"
#define TR_MAVLINK_NAV_MENU_TITLE "NAV"
#define TR_MAVLINK_COURSE "Carrera"
#define TR_MAVLINK_HEADING "Titulo"
#define TR_MAVLINK_BEARING "Soporte"
#define TR_MAVLINK_ALTITUDE "Altitud"
#define TR_MAVLINK_GPS "GPS"
#define TR_MAVLINK_NO_FIX "NO Fix"
#define TR_MAVLINK_SAT "SAT"
#define TR_MAVLINK_HDOP "HDOP"
#define TR_MAVLINK_LAT "LAT"
#define TR_MAVLINK_LON "LON"
#endif
// Horus and Taranis column headers
#define TR_PHASES_HEADERS_NAME "Nombre"

View file

@ -139,8 +139,6 @@
#define TR_RETA123 "RETA123LR"
#elif defined(PCBSKY9X)
#define TR_RETA123 "RETA123a"
#elif defined(CPUM2560)
#define TR_RETA123 "RETA123ab"
#else
#define TR_RETA123 "RETA123"
#endif
@ -169,11 +167,7 @@
#define TR_IRPROTOS
#endif
#if defined(CPUARM)
#define TR_XPPM
#else
#define TR_XPPM "PPM16\0""PPMsim"
#endif
#define TR_VPROTOS "PPM\0 " TR_XPPM TR_PXX TR_DSM2 TR_IRPROTOS
@ -210,27 +204,14 @@
#else
#define TR_CSWTIMER "Tim\0 "
#define TR_CSWSTICKY "Glue\0"
#if defined(CPUARM)
#define TR_CSWRANGE "Rnge\0"
#define TR_CSWSTAY "Edge\0"
#else
#define TR_CSWRANGE
#define TR_CSWSTAY
#endif
#endif
#if defined(CPUARM)
#define TR_CSWEQUAL "a=x\0 "
#else
#define TR_CSWEQUAL
#endif
#define LEN_VCSWFUNC "\005"
#if defined(CPUARM)
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""Δ}x\0 ""|Δ|}x" TR_CSWTIMER TR_CSWSTICKY
#else
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""^}x\0 ""|^|}x" TR_CSWTIMER TR_CSWSTICKY
#endif
#define LEN_VFSWFUNC "\012"
@ -306,13 +287,7 @@
#define TR_SF_RESERVE "[reserve]\0"
#if defined(CPUARM)
#define TR_VFSWFUNC TR_SF_SAFETY "Trainer\0 ""Inst. Trim""Reset\0 ""Set \0 " TR_ADJUST_GVAR "Volume\0 " "SetFailsfe" "RangeCheck" "ModuleBind" TR_SOUND TR_PLAY_TRACK TR_PLAY_VALUE TR_SF_RESERVE TR_SF_PLAY_SCRIPT TR_SF_RESERVE TR_SF_BG_MUSIC TR_VVARIO TR_HAPTIC TR_SDCLOGS "Backlight\0" TR_SF_SCREENSHOT TR_SF_TEST
#elif defined(PCBGRUVIN9X)
#define TR_VFSWFUNC TR_SF_SAFETY "Trainer\0 ""Inst. Trim""Reset\0 " TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC TR_SDCLOGS "Backlight\0" TR_SF_TEST
#else
#define TR_VFSWFUNC TR_SF_SAFETY "Trainer\0 ""Inst. Trim""Reset\0 " TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC "Backlight\0" TR_SF_TEST
#endif
#define LEN_VFSWRESET TR("\004", "\011")
@ -332,10 +307,8 @@
#if defined(PCBTARANIS)
#define TR_FSW_RESET_TIMERS "Timer 1\0 ""Timer 2\0 ""Timer 3\0 "
#elif defined(CPUARM)
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#else
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2"
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#endif
#define TR_VFSWRESET TR(TR_FSW_RESET_TIMERS "All\0" TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC, TR_FSW_RESET_TIMERS "All\0 " TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC)
@ -345,21 +318,12 @@
#define LEN_VTELEMCHNS "\004"
#if defined(CPUARM)
#define TR_TELEM_RESERVE TR("[--]", "[---]")
#define TR_TELEM_TIME TR("Time", "Time\0")
#define TR_RAS 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_RAS
#define TR_RX_BATT
#define TR_A3_A4
#define TR_A3_A4_MIN
#endif
#define TR_ASPD_MAX TR("ASp+", "ASpd+")
@ -369,33 +333,17 @@
#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
#define LENGTH_UNIT_IMP "ft\0"
#define SPEED_UNIT_IMP "mph"
#define LENGTH_UNIT_METR "m\0 "
#define SPEED_UNIT_METR "kmh"
#if defined(CPUARM)
#define LEN_VUNITSSYSTEM TR("\006", "\010")
#define TR_VUNITSSYSTEM TR("Metric""Imper.", "Metric\0 ""Imperial")
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "-\0 ""V\0 ""A\0 ""mA\0""kts""m/s""f/s""kmh""mph""m\0 ""ft\0""@C\0""@F\0""%\0 ""mAh""W\0 ""mW\0""dB\0""rpm""g\0 ""@\0 ""rad""ml\0""fOz"
#else
#if defined(IMPERIAL_UNITS)
#define LENGTH_UNIT LENGTH_UNIT_IMP
#define SPEED_UNIT SPEED_UNIT_IMP
#else
#define LENGTH_UNIT LENGTH_UNIT_METR
#define SPEED_UNIT SPEED_UNIT_METR
#endif
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "V\0 ""A\0 ""m/s""-\0 " SPEED_UNIT LENGTH_UNIT "@\0 ""%\0 ""mA\0""mAh""W\0 "
#endif
#define STR_V (STR_VTELEMUNIT+1)
#define STR_A (STR_VTELEMUNIT+4)
@ -409,15 +357,10 @@
#define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "None\0 ""Hub\0 ""WSHHigh"
#if defined(CPUARM)
#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("A1\0""A2\0""A3\0""A4\0""FAS""Cel", "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"
#if defined(TELEMETRY_FRSKY_SPORT)
@ -491,11 +434,7 @@
#define TR_9X_3POS_SWITCHES "ID0""ID1""ID2"
#endif
#if defined(CPUARM)
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12""L13""L14""L15""L16""L17""L18""L19""L20""L21""L22""L23""L24""L25""L26""L27""L28""L29""L30""L31""L32"
#else
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12"
#endif
#if defined(PCBHORUS)
#define TR_TRIMS_SWITCHES "\313Rl""\313Rr""\313Ed""\313Eu""\313Td""\313Tu""\313Al""\313Ar""\3135d""\3135u""\3136d""\3136u"
@ -506,9 +445,6 @@
#if defined(PCBSKY9X)
#define TR_ROTARY_ENCODERS "REa\0"
#define TR_ROTENC_SWITCHES "REa"
#elif defined(PCBGRUVIN9X) || defined(PCBMEGA2560)
#define TR_ROTARY_ENCODERS "REa\0""REb\0"
#define TR_ROTENC_SWITCHES "REa""REb"
#else
#define TR_ROTARY_ENCODERS
#define TR_ROTENC_SWITCHES
@ -535,13 +471,8 @@
#define TR_CYC_VSRCRAW "[C1]""[C2]""[C3]"
#endif
#if defined(CPUARM)
#define TR_RESERVE_VSRCRAW "[--]"
#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
@ -559,14 +490,6 @@
#define LEN_VFAILSAFE "\011"
#define TR_VFAILSAFE "Not set\0 ""Hold\0 ""Custom\0 ""No pulses""Receiver\0"
#if defined(TELEMETRY_MAVLINK)
#define LEN_MAVLINK_BAUDS "\006"
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""58798 ""76800"
#define LEN_MAVLINK_AC_MODES "\011"
#define TR_MAVLINK_AC_MODES "Stabilize""Acro ""Alt Hold ""Auto ""Guided ""Loiter ""RTL ""Circle ""Pos Hold ""Land ""OF Loiter""Toy A ""Toy M ""INVALID "
#define LEN_MAVLINK_AP_MODES "\015"
#define TR_MAVLINK_AP_MODES "Manual ""Circle ""Stabilize ""Training ""Fly by Wire A""Fly by Wire A""Auto ""RTL ""Loiter ""Guided ""Initialising ""INVALID "
#endif
#define LEN_VSENSORTYPES "\012"
#define TR_VSENSORTYPES "Custom\0 ""Calculated"
@ -763,13 +686,8 @@
#define TR_TMR1LATMINUS "Tmr1Lat min\037\124us"
#define TR_TMR1JITTERUS "Tmr1 Jitter\037\124us"
#if defined(CPUARM)
#define TR_TMIXMAXMS "Tmix max"
#define TR_FREESTACKMINB "Free Stack"
#else
#define TR_TMIXMAXMS "Tmix max\037\124ms"
#define TR_FREESTACKMINB "Free Stack\037\124b"
#endif
#define TR_MENUTORESET CENTER TR_ENTER " to reset"
#define TR_PPM_TRAINER "TR"
@ -1093,31 +1011,6 @@
#define TR_CONFIRMRESET "Erase ALL models and settings?"
#define TR_TO_MANY_LUA_SCRIPTS "Too many Lua scripts!"
#if defined(TELEMETRY_MAVLINK)
#define TR_MAVLINK_RC_RSSI_SCALE_LABEL "Max RSSI"
#define TR_MAVLINK_PC_RSSI_EN_LABEL "PC RSSI EN"
#define TR_MAVMENUSETUP_TITLE "Mavlink Setup"
#define TR_MAVLINK_BAUD_LABEL "Baudrate"
#define TR_MAVLINK_INFOS "INFOS"
#define TR_MAVLINK_MODE "MODE"
#define TR_MAVLINK_CUR_MODE "Current Mode"
#define TR_MAVLINK_ARMED "Armed"
#define TR_MAVLINK_BAT_MENU_TITLE "BAT RSSI"
#define TR_MAVLINK_BATTERY_LABEL "Flight Battery status"
#define TR_MAVLINK_RC_RSSI_LABEL "RC RSSI"
#define TR_MAVLINK_PC_RSSI_LABEL "PC RSSI"
#define TR_MAVLINK_NAV_MENU_TITLE "NAV"
#define TR_MAVLINK_COURSE "Course"
#define TR_MAVLINK_HEADING "Heading"
#define TR_MAVLINK_BEARING "Bearing"
#define TR_MAVLINK_ALTITUDE "Altitude"
#define TR_MAVLINK_GPS "GPS"
#define TR_MAVLINK_NO_FIX "NO Fix"
#define TR_MAVLINK_SAT "SAT"
#define TR_MAVLINK_HDOP "HDOP"
#define TR_MAVLINK_LAT "LAT"
#define TR_MAVLINK_LON "LON"
#endif
// Horus and Taranis column headers
#define TR_PHASES_HEADERS_NAME "Name"

View file

@ -139,8 +139,6 @@
#define TR_RETA123 "DPGA123LR"
#elif defined(PCBSKY9X)
#define TR_RETA123 "DPGA123a"
#elif defined(CPUM2560)
#define TR_RETA123 "DPGA123ab"
#else
#define TR_RETA123 "DPGA123"
#endif
@ -169,11 +167,7 @@
#define TR_IRPROTOS
#endif
#if defined(CPUARM)
#define TR_XPPM
#else
#define TR_XPPM "PPM16\0""PPMsim"
#endif
#define TR_VPROTOS "PPM\0 " TR_XPPM TR_PXX TR_DSM2 TR_IRPROTOS
@ -210,27 +204,14 @@
#else
#define TR_CSWTIMER "Temp\0"
#define TR_CSWSTICKY "Bist\0"
#if defined(CPUARM)
#define TR_CSWRANGE "Zone\0"
#define TR_CSWSTAY "Flnc\0"
#else
#define TR_CSWRANGE
#define TR_CSWSTAY
#endif
#endif
#if defined(CPUARM)
#define TR_CSWEQUAL "a=x\0 "
#else
#define TR_CSWEQUAL
#endif
#define LEN_VCSWFUNC "\005"
#if defined(CPUARM)
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""ET\0 ""OU\0 ""OUX\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""Δ}x\0 ""|Δ|}x" TR_CSWTIMER TR_CSWSTICKY
#else
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""ET\0 ""OU\0 ""OUX\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""^}x\0 ""|^|}x" TR_CSWTIMER TR_CSWSTICKY
#endif
#define LEN_VFSWFUNC "\015"
@ -308,13 +289,7 @@
#define TR_SF_RESERVE "[reserve]\0 "
#if defined(CPUARM)
#define TR_VFSWFUNC TR_SF_SAFETY "Ecolage\0 ""Trim instant.""Remise à 0\0 ""Déf.\0 " TR_ADJUST_GVAR "Volume\0 " "DéfFailsafe\0 " "Test Port.\0 " "Bind\0 " TR_SOUND TR_PLAY_TRACK TR_PLAY_VALUE TR_SF_RESERVE TR_SF_PLAY_SCRIPT TR_SF_RESERVE TR_SF_BG_MUSIC TR_VVARIO TR_HAPTIC TR_SDCLOGS "Rétroécl.\0 " TR_SF_SCREENSHOT TR_SF_TEST
#elif defined(PCBGRUVIN9X)
#define TR_VFSWFUNC TR_SF_SAFETY "Ecolage\0 ""Trim instant.""Remise à 0\0 " TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC TR_SDCLOGS "Rétroécl.\0 " TR_SF_TEST
#else
#define TR_VFSWFUNC TR_SF_SAFETY "Ecolage\0 ""Trim instant.""Remise à 0\0 " TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC "Rétroécl.\0 " TR_SF_TEST
#endif
#define LEN_VFSWRESET TR("\004", "\012")
@ -334,10 +309,8 @@
#if LCD_W >= 212
#define TR_FSW_RESET_TIMERS "Chrono 1\0 ""Chrono 2\0 ""Chrono 3\0 "
#elif defined(CPUARM)
#define TR_FSW_RESET_TIMERS "Chr1""Chr2""Chr3"
#else
#define TR_FSW_RESET_TIMERS "Chr1""Chr2"
#define TR_FSW_RESET_TIMERS "Chr1""Chr2""Chr3"
#endif
#define TR_VFSWRESET TR(TR_FSW_RESET_TIMERS "Tout" TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC, TR_FSW_RESET_TIMERS "Tout\0 " TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC)
@ -347,21 +320,12 @@
#define LEN_VTELEMCHNS "\004"
#if defined(CPUARM)
#define TR_TELEM_RESERVE TR("[--]", "[---]")
#define TR_TELEM_TIME TR("Heur", "H:M\0 ")
#define TR_RAS TR("SWR\0", "SWR\0 ")
#define TR_RX_BATT TR("BtRx", "BatRx")
#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_RAS
#define TR_RX_BATT
#define TR_A3_A4
#define TR_A3_A4_MIN
#endif
#define TR_ASPD_MAX TR("ViA+", "VitA+")
@ -371,33 +335,17 @@
#define TR_TELEM_RSSI_RX TR("Rx\0 ", "Rx\0 ")
#endif
#if defined(CPUARM)
#define TR_TELEM_TIMERS TR("Chr1""Chr2""Chr3", "Chr1\0""Chr2\0""Chr3\0")
#else
#define TR_TELEM_TIMERS TR("Chr1""Chr2", "Chr1\0""Chr2\0")
#endif
#define LENGTH_UNIT_IMP "ft\0"
#define SPEED_UNIT_IMP "mph"
#define LENGTH_UNIT_METR "m\0 "
#define SPEED_UNIT_METR "kmh"
#if defined(CPUARM)
#define LEN_VUNITSSYSTEM TR("\006", "\012")
#define TR_VUNITSSYSTEM TR("Métr.\0""Impér.", "Métriques\0""Impériales")
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "-\0 ""V\0 ""A\0 ""mA\0""kts""m/s""f/s""kmh""mph""m\0 ""ft\0""@C\0""@F\0""%\0 ""mAh""W\0 ""mW\0""dB\0""rpm""g\0 ""@\0 ""rad""ml\0""fOz"
#else
#if defined(IMPERIAL_UNITS)
#define LENGTH_UNIT LENGTH_UNIT_IMP
#define SPEED_UNIT SPEED_UNIT_IMP
#else
#define LENGTH_UNIT LENGTH_UNIT_METR
#define SPEED_UNIT SPEED_UNIT_METR
#endif
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "V\0 ""A\0 ""m/s""-\0 " SPEED_UNIT LENGTH_UNIT "@\0 ""%\0 ""mA\0""mAh""W\0 "
#endif
#define STR_V (STR_VTELEMUNIT+1)
#define STR_A (STR_VTELEMUNIT+4)
@ -411,15 +359,10 @@
#define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "Aucun ""Hub\0 ""WSHHigh"
#if defined(CPUARM)
#define LEN_AMPSRC TR("\003", "\005")
#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 ""Elem.")
#define LEN_VOLTSRC TR("\003", "\005")
#define TR_VOLTSRC TR("A1\0""A2\0""A3\0""A4\0""FAS""Cel", "A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Elem.")
#else
#define LEN_AMPSRC TR("\003", "\005")
#define TR_AMPSRC TR("---""A1\0""A2\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""FAS\0 ""Elem.")
#endif
#define LEN_VARIOSRC "\005"
#if defined(TELEMETRY_FRSKY_SPORT)
@ -428,13 +371,8 @@
#define TR_VARIOSRC "Alti\0""Alti+""Vario""A1\0 ""A2\0"
#endif
#if defined(CPUARM)
#define LEN_VTELEMSCREENTYPE "\007"
#define TR_VTELEMSCREENTYPE "Rien\0 ""Valeurs""Barres\0""Script\0"
#else
#define LEN_VTELEMSCREENTYPE "\004"
#define TR_VTELEMSCREENTYPE "Val.""Bars"
#endif
#define LEN_GPSFORMAT "\004"
#define TR_GPSFORMAT "DMS\0""NMEA"
@ -473,18 +411,12 @@
#define LEN_VSWITCHES "\003"
#define LEN_VSRCRAW "\004"
#if defined(CPUARM)
#define TR_STICKS_VSRCRAW "\307Dir""\307Prf""\307Gaz""\307Ail"
#else
#define TR_STICKS_VSRCRAW "Dir\0""Prf\0""Gaz\0""Ail\0"
#endif
#if defined(PCBHORUS)
#define TR_TRIMS_VSRCRAW "\313Dir""\313Prf""\313Gaz""\313Ail""\313T5\0""\313T6\0"
#elif defined(CPUARM)
#define TR_TRIMS_VSRCRAW "\313Dir""\313Prf""\313Gaz""\313Ail"
#else
#define TR_TRIMS_VSRCRAW "TrmD""TrmP""TrmG""TrmA"
#define TR_TRIMS_VSRCRAW "\313Dir""\313Prf""\313Gaz""\313Ail"
#endif
#if defined(PCBX12S)
@ -515,11 +447,7 @@
#define TR_9X_3POS_SWITCHES "ID0""ID1""ID2"
#endif
#if defined(CPUARM)
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12""L13""L14""L15""L16""L17""L18""L19""L20""L21""L22""L23""L24""L25""L26""L27""L28""L29""L30""L31""L32"
#else
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12"
#endif
#if defined(PCBHORUS)
#define TR_TRIMS_SWITCHES "\313Dg""\313Dd""\313Pb""\313Ph""\313Gb""\313Gh""\313Ag""\313Ad""\3135d""\3135u""\3136d""\3136u"
@ -530,9 +458,6 @@
#if defined(PCBSKY9X)
#define TR_ROTARY_ENCODERS "REa\0"
#define TR_ROTENC_SWITCHES "REa"
#elif defined(PCBGRUVIN9X) || defined(PCBMEGA2560)
#define TR_ROTARY_ENCODERS "REa\0""REb\0"
#define TR_ROTENC_SWITCHES "REa""REb"
#else
#define TR_ROTARY_ENCODERS
#define TR_ROTENC_SWITCHES
@ -559,13 +484,8 @@
#define TR_CYC_VSRCRAW "[C1]""[C2]""[C3]"
#endif
#if defined(CPUARM)
#define TR_RESERVE_VSRCRAW "[--]"
#define TR_EXTRA_VSRCRAW "Batt""H:M\0""GPS\0" TR_RESERVE_VSRCRAW TR_RESERVE_VSRCRAW TR_RESERVE_VSRCRAW TR_RESERVE_VSRCRAW "Chr1""Chr2""Chr3"
#else
#define TR_EXTRA_VSRCRAW
#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_RAS "Tx\0 " TR_TELEM_RSSI_RX TR_RX_BATT "A1\0 ""A2\0 " TR_A3_A4 "Alt\0""Rpm\0""Carb""T1\0 ""T2\0 ""Vit\0""Dist""AltG""Elem""Velm""Vfas""Cour""Cnsm""Puis""AccX""AccY""AccZ""Cap\0""VitV""VitA""dET\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""Vit+""Dst+" TR_ASPD_MAX "Elm-""Els-""Vfs-""Cur+""Pui+" TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE "Acc\0""Tmps"
#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
@ -583,14 +503,6 @@
#define LEN_VFAILSAFE "\011"
#define TR_VFAILSAFE TR("Pas déf.\0""Maintien\0""Prédéf.\0 ""Pas d'imp""Récepteur", "Pas déf.\0""Maintien\0""Prédéfini""Pas d'imp""Récepteur")
#if defined(TELEMETRY_MAVLINK)
#define LEN_MAVLINK_BAUDS "\006"
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""58798 ""76800"
#define LEN_MAVLINK_AC_MODES "\011"
#define TR_MAVLINK_AC_MODES "Stabilize""Acro ""Alt Hold ""Auto ""Guided ""Loiter ""RTL ""Circle ""Pos Hold ""Land ""OF Loiter""Toy A ""Toy M ""INVALID "
#define LEN_MAVLINK_AP_MODES "\015"
#define TR_MAVLINK_AP_MODES "Manual ""Circle ""Stabilize ""Training ""Fly by Wire A""Fly by Wire A""Auto ""RTL ""Loiter ""Guided ""Initialising ""INVALID "
#endif
#define LEN_VSENSORTYPES "\012"
#define TR_VSENSORTYPES "Perso\0 ""Calculé\0 "
@ -670,13 +582,9 @@
#define TR_OUTPUT_TYPE INDENT "Sortie"
#endif
#define TR_PROTO TR(INDENT "Proto.", INDENT "Protocole")
#if defined(CPUARM)
#define TR_PPMFRAME INDENT "Trame PPM"
#define TR_REFRESHRATE TR(INDENT "Refresh", INDENT "Refresh rate")
#define STR_WARN_BATTVOLTAGE TR(INDENT "Output is VBAT: ", INDENT "Warning: output level is VBAT: ")
#else
#define TR_PPMFRAME "Trame PPM"
#endif
#define TR_MS "ms"
#define TR_SWITCH TR("Inter", "Interrupteur")
#define TR_TRIMS "Trims"
@ -799,13 +707,8 @@
#define TR_TMR1LATMINUS "Tmr1Lat min\037\124us"
#define TR_TMR1JITTERUS "Tmr1 Jitter\037\124us"
#if defined(CPUARM)
#define TR_TMIXMAXMS "Tmix max"
#define TR_FREESTACKMINB "Free Stack"
#else
#define TR_TMIXMAXMS "Tmix max\037\124ms"
#define TR_FREESTACKMINB "Free Stack\037\124b"
#endif
#define TR_MENUTORESET CENTER TR_ENTER" pour reset"
#define TR_PPM_TRAINER "TR"
@ -848,13 +751,8 @@
#define TR_MENUFLIGHTMODES "PHASES DE VOL"
#define TR_MENUHELISETUP TR("CONF.HELI", "CONFIGURATION HELICO")
#if defined(CPUARM)
#define TR_MENUINPUTS "ENTREES"
#define TR_MENULIMITS "SORTIES"
#else
#define TR_MENUINPUTS "DR/EXPO"
#define TR_MENULIMITS "LIMITES"
#endif
#define TR_MENUCURVES "COURBES"
#define TR_MENUCURVE "COURBE"
@ -873,13 +771,8 @@
#define TR_MONITOR_SWITCHES "INTERS LOGIQUES"
#define TR_MONITOR_OUTPUT_DESC "Sorties"
#define TR_MONITOR_MIXER_DESC "Mixeurs"
#if defined(CPUARM)
#define TR_RECEIVER_NUM TR(INDENT "NumRx", INDENT "No. récepteur")
#define TR_RECEIVER INDENT "Récepteur"
#else
#define TR_RECEIVER_NUM "Récepteur"
#define TR_RECEIVER "Récepteur"
#endif
#define TR_MULTI_RFTUNE TR(INDENT "Ajust.fréq", INDENT "Ajustement fréq.")
#define TR_MULTI_TELEMETRY "Télémétrie"
#define TR_MULTI_VIDFREQ TR(INDENT "Fréq. vidéo", INDENT "Fréquence vidéo")
@ -1138,31 +1031,6 @@
#define TR_CONFIRMRESET TR("Effacer TOUT?","Effacer TOUS modèles/réglages?")
#define TR_TO_MANY_LUA_SCRIPTS "Trop de scripts lua!"
#if defined(TELEMETRY_MAVLINK)
#define TR_MAVLINK_RC_RSSI_SCALE_LABEL "RSSI Max"
#define TR_MAVLINK_PC_RSSI_EN_LABEL "PC RSSI EN"
#define TR_MAVMENUSETUP_TITLE "Config Mavlink"
#define TR_MAVLINK_BAUD_LABEL "Baudrate"
#define TR_MAVLINK_INFOS "INFOS"
#define TR_MAVLINK_MODE "MODE"
#define TR_MAVLINK_CUR_MODE "Mode courant"
#define TR_MAVLINK_ARMED "Armé"
#define TR_MAVLINK_BAT_MENU_TITLE "BAT RSSI"
#define TR_MAVLINK_BATTERY_LABEL "Accu propulsion"
#define TR_MAVLINK_RC_RSSI_LABEL "RC RSSI"
#define TR_MAVLINK_PC_RSSI_LABEL "PC RSSI"
#define TR_MAVLINK_NAV_MENU_TITLE "NAV"
#define TR_MAVLINK_COURSE "Course"
#define TR_MAVLINK_HEADING "Cap"
#define TR_MAVLINK_BEARING "Relèv."
#define TR_MAVLINK_ALTITUDE "Altitude"
#define TR_MAVLINK_GPS "GPS"
#define TR_MAVLINK_NO_FIX "NO Fix"
#define TR_MAVLINK_SAT "SAT"
#define TR_MAVLINK_HDOP "HDOP"
#define TR_MAVLINK_LAT "LAT"
#define TR_MAVLINK_LON "LON"
#endif
// Horus and Taranis column headers
#define TR_PHASES_HEADERS_NAME "Nom"

View file

@ -139,8 +139,6 @@
#define TR_RETA123 "DEMA123SD"
#elif defined(PCBSKY9X)
#define TR_RETA123 "DEMA123a"
#elif defined(CPUM2560)
#define TR_RETA123 "DEMA123ab"
#else
#define TR_RETA123 "DEMA123"
#endif
@ -169,11 +167,7 @@
#define TR_IRPROTOS
#endif
#if defined(CPUARM)
#define TR_XPPM
#else
#define TR_XPPM "PPM16\0""PPMsim"
#endif
#define TR_VPROTOS "PPM\0 " TR_XPPM TR_PXX TR_DSM2 TR_IRPROTOS
@ -210,27 +204,14 @@
#else
#define TR_CSWTIMER "Tim\0 "
#define TR_CSWSTICKY "Glue\0"
#if defined(CPUARM)
#define TR_CSWRANGE "Rnge\0"
#define TR_CSWSTAY "Edge\0"
#else
#define TR_CSWRANGE
#define TR_CSWSTAY
#endif
#endif
#if defined(CPUARM)
#define TR_CSWEQUAL "a=x\0 "
#else
#define TR_CSWEQUAL
#endif
#define LEN_VCSWFUNC "\005"
#if defined(CPUARM)
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""Δ}x\0 ""|Δ|}x" TR_CSWTIMER TR_CSWSTICKY
#else
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""^}x\0 ""|^|}x" TR_CSWTIMER TR_CSWSTICKY
#endif
#define LEN_VFSWFUNC "\015"
@ -308,13 +289,7 @@
#define TR_SF_RESERVE "[riserva] \0"
#if defined(CPUARM)
#define TR_VFSWFUNC TR_SF_SAFETY "Maestro \0 ""Trim Instant.""Azzera\0 ""Set \0 " TR_ADJUST_GVAR "Volume\0 " "SetFailsafe\0 " "RangeCheck\0 " "ModuleBind\0 " TR_SOUND TR_PLAY_TRACK TR_PLAY_VALUE TR_SF_RESERVE TR_SF_PLAY_SCRIPT TR_SF_RESERVE TR_SF_BG_MUSIC TR_VVARIO TR_HAPTIC TR_SDCLOGS "Retroillum.\0 " TR_SF_SCREENSHOT TR_SF_TEST
#elif defined(PCBGRUVIN9X)
#define TR_VFSWFUNC TR_SF_SAFETY "Maestro \0 ""Trim Instant.""Azzera\0 " TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC TR_SDCLOGS "Retroillum.\0 " TR_SF_TEST
#else
#define TR_VFSWFUNC TR_SF_SAFETY "Maestro \0 ""Trim Instant.""Azzera\0 " TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC "Retroillum.\0 " TR_SF_TEST
#endif
#define LEN_VFSWRESET TR("\004", "\011")
@ -334,10 +309,8 @@
#if LCD_W >= 212
#define TR_FSW_RESET_TIMERS "Timer 1\0 ""Timer 2\0 ""Timer 3\0 "
#elif defined(CPUARM)
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#else
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2"
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#endif
#define TR_VFSWRESET TR(TR_FSW_RESET_TIMERS "All\0" TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC, TR_FSW_RESET_TIMERS "Tutto\0 " TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC)
@ -347,21 +320,12 @@
#define LEN_VTELEMCHNS "\004"
#if defined(CPUARM)
#define TR_TELEM_RESERVE TR("[--]", "[---]")
#define TR_TELEM_TIME TR("Ora\0", "Ora\0 ")
#define TR_RAS TR("SWR\0", "SWR\0 ")
#define TR_RX_BATT TR("RxBt", "BatRx")
#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_RAS
#define TR_RX_BATT
#define TR_A3_A4
#define TR_A3_A4_MIN
#endif
#define TR_ASPD_MAX TR("ASp+", "ASpd+")
@ -371,33 +335,17 @@
#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
#define LENGTH_UNIT_IMP "ft\0"
#define SPEED_UNIT_IMP "mph"
#define LENGTH_UNIT_METR "m\0 "
#define SPEED_UNIT_METR "kmh"
#if defined(CPUARM)
#define LEN_VUNITSSYSTEM TR("\006", "\011")
#define TR_VUNITSSYSTEM TR("Metric""Imper.", "Metriche\0""Imperiali")
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "-\0 ""V\0 ""A\0 ""mA\0""kts""m/s""f/s""kmh""mph""m\0 ""ft\0""@C\0""@F\0""%\0 ""mAh""W\0 ""mW\0""dB\0""rpm""g\0 ""@\0 ""rad""ml\0""fOz"
#else
#if defined(IMPERIAL_UNITS)
#define LENGTH_UNIT LENGTH_UNIT_IMP
#define SPEED_UNIT SPEED_UNIT_IMP
#else
#define LENGTH_UNIT LENGTH_UNIT_METR
#define SPEED_UNIT SPEED_UNIT_METR
#endif
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "V\0 ""A\0 ""m/s""-\0 " SPEED_UNIT LENGTH_UNIT "@\0 ""%\0 ""mA\0""mAh""W\0 "
#endif
#define STR_V (STR_VTELEMUNIT+1)
#define STR_A (STR_VTELEMUNIT+4)
@ -411,15 +359,10 @@
#define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "---\0 ""Hub\0 ""WSHHigh"
#if defined(CPUARM)
#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 ""Celle\0 ")
#define LEN_VOLTSRC TR("\003", "\007")
#define TR_VOLTSRC TR("A1\0""A2\0""A3\0""A4\0""FAS""Cel", "A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Celle\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 ""Celle\0 ")
#endif
#define LEN_VARIOSRC "\005"
#if defined(TELEMETRY_FRSKY_SPORT)
@ -428,13 +371,8 @@
#define TR_VARIOSRC "Alti\0""Alti+""Vario""A1\0 ""A2\0"
#endif
#if defined(CPUARM)
#define LEN_VTELEMSCREENTYPE "\006"
#define TR_VTELEMSCREENTYPE "Niente""Valori""Barre\0""Script"
#else
#define LEN_VTELEMSCREENTYPE "\006"
#define TR_VTELEMSCREENTYPE "Valori""Barre\0"
#endif
#define LEN_GPSFORMAT "\004"
#define TR_GPSFORMAT "HMS NMEA"
@ -498,11 +436,7 @@
#define TR_9X_3POS_SWITCHES "ID0""ID1""ID2"
#endif
#if defined(CPUARM)
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12""L13""L14""L15""L16""L17""L18""L19""L20""L21""L22""L23""L24""L25""L26""L27""L28""L29""L30""L31""L32"
#else
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12"
#endif
#if defined(PCBHORUS)
#define TR_TRIMS_SWITCHES "\313Rl""\313Rr""\313Ed""\313Eu""\313Td""\313Tu""\313Al""\313Ar""\3135d""\3135u""\3136d""\3136u"
@ -513,9 +447,6 @@
#if defined(PCBSKY9X)
#define TR_ROTARY_ENCODERS "REa\0"
#define TR_ROTENC_SWITCHES "REa"
#elif defined(PCBGRUVIN9X) || defined(PCBMEGA2560)
#define TR_ROTARY_ENCODERS "REa\0""REb\0"
#define TR_ROTENC_SWITCHES "REa""REb"
#else
#define TR_ROTARY_ENCODERS
#define TR_ROTENC_SWITCHES
@ -542,13 +473,8 @@
#define TR_CYC_VSRCRAW "[C1]""[C2]""[C3]"
#endif
#if defined(CPUARM)
#define TR_RESERVE_VSRCRAW "[--]"
#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" TR_TELEM_TIME TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_TIMERS TR_RAS "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""Ora\0"
#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
@ -566,14 +492,6 @@
#define LEN_VFAILSAFE "\013"
#define TR_VFAILSAFE "Non settato""Mantieni\0 ""Personali\0 ""No impulsi\0""Ricevente\0 "
#if defined(TELEMETRY_MAVLINK)
#define LEN_MAVLINK_BAUDS "\006"
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""58798 ""76800"
#define LEN_MAVLINK_AC_MODES "\011"
#define TR_MAVLINK_AC_MODES "Stabilize""Acro ""Alt Hold ""Auto ""Guided ""Loiter ""RTL ""Circle ""Pos Hold ""Land ""OF Loiter""Toy A ""Toy M ""INVALID "
#define LEN_MAVLINK_AP_MODES "\015"
#define TR_MAVLINK_AP_MODES "Manual ""Circle ""Stabilize ""Training ""Fly by Wire A""Fly by Wire A""Auto ""RTL ""Loiter ""Guided ""Inizializza ""INVALID "
#endif
#define LEN_VSENSORTYPES "\012"
#define TR_VSENSORTYPES "Custom\0 ""Calcolato\0"
@ -638,11 +556,7 @@
#define TR_PHASENAME "Nome fase"
#define TR_MIXNAME "Nome mix"
#define TR_INPUTNAME "Nome Ingr."
#if defined(CPUARM)
#define TR_EXPONAME "Nome expo"
#else
#define TR_EXPONAME "Nome Expo"
#endif
#define TR_BITMAP "Immagine"
#define TR_TIMER TR("Timer","Timer ")
#define TR_ELIMITS TR("Limiti.E","Limiti Estesi")
@ -657,13 +571,9 @@
#define TR_OUTPUT_TYPE INDENT "Output"
#endif
#define TR_PROTO TR(INDENT "Proto", INDENT "Protocollo")
#if defined(CPUARM)
#define TR_PPMFRAME INDENT "PPM frame"
#define TR_REFRESHRATE TR(INDENT "Refresh", INDENT "Refresh rate")
#define STR_WARN_BATTVOLTAGE TR(INDENT "Output is VBAT: ", INDENT "Warning: output level is VBAT: ")
#else
#define TR_PPMFRAME "PPM frame"
#endif
#define TR_MS "ms"
#define TR_SWITCH "Inter."
#define TR_TRIMS "Trims"
@ -786,13 +696,8 @@
#define TR_TMR1LATMINUS "Tmr1Lat min\037\124us"
#define TR_TMR1JITTERUS "Tmr1 Jitter\037\124us"
#if defined(CPUARM)
#define TR_TMIXMAXMS "Tmix max"
#define TR_FREESTACKMINB "Free Stack"
#else
#define TR_TMIXMAXMS "Tmix max\037\124ms"
#define TR_FREESTACKMINB "Free Stack\037\124b"
#endif
#define TR_MENUTORESET CENTER TR_ENTER" x Azzerare"
#define TR_PPM_TRAINER "TR"
@ -835,13 +740,8 @@
#define TR_MENUFLIGHTMODES "FASI DI VOLO"
#define TR_MENUHELISETUP "CONFIGURA ELI"
#if defined(CPUARM)
#define TR_MENUINPUTS "INGRESSI"
#define TR_MENULIMITS "USCITE"
#else
#define TR_MENUINPUTS "DR/ESPO"
#define TR_MENULIMITS "LIMITI"
#endif
#define TR_MENUCURVES "CURVE"
#define TR_MENUCURVE "CURVA"
@ -860,13 +760,8 @@
#define TR_MONITOR_CHANNELS4 "CHANNELS MONITOR 25/32"
#define TR_MONITOR_OUTPUT_DESC "Outputs"
#define TR_MONITOR_MIXER_DESC "Mixers"
#if defined(CPUARM)
#define TR_RECEIVER_NUM TR(INDENT "RxNum", INDENT "Ricevente No.")
#define TR_RECEIVER INDENT "Receiver"
#else
#define TR_RECEIVER_NUM "RxNum"
#define TR_RECEIVER "RxNum"
#endif
#define TR_MULTI_RFTUNE TR(INDENT "Freq tune",INDENT "RF Freq. fine tune")
#define TR_MULTI_TELEMETRY "Telemetry"
#define TR_MULTI_VIDFREQ TR(INDENT "Vid. freq.", INDENT "Video frequency")
@ -1118,31 +1013,6 @@
#define TR_CONFIRMRESET "Resettare TUTTI i dati?"
#define TR_TO_MANY_LUA_SCRIPTS "Troppi Scripts Lua!"
#if defined(TELEMETRY_MAVLINK)
#define TR_MAVLINK_RC_RSSI_SCALE_LABEL "Max RSSI"
#define TR_MAVLINK_PC_RSSI_EN_LABEL "PC RSSI EN"
#define TR_MAVMENUSETUP_TITLE "Setta Mavlink"
#define TR_MAVLINK_BAUD_LABEL "Baudrate"
#define TR_MAVLINK_INFOS "INFOS"
#define TR_MAVLINK_MODE "MODO"
#define TR_MAVLINK_CUR_MODE "Modo Corrente"
#define TR_MAVLINK_ARMED "Armato"
#define TR_MAVLINK_BAT_MENU_TITLE "BAT RSSI"
#define TR_MAVLINK_BATTERY_LABEL "Stato batteria di volo"
#define TR_MAVLINK_RC_RSSI_LABEL "RC RSSI"
#define TR_MAVLINK_PC_RSSI_LABEL "PC RSSI"
#define TR_MAVLINK_NAV_MENU_TITLE "NAV"
#define TR_MAVLINK_COURSE "Course"
#define TR_MAVLINK_HEADING "Heading"
#define TR_MAVLINK_BEARING "Bearing"
#define TR_MAVLINK_ALTITUDE "Altitudine"
#define TR_MAVLINK_GPS "GPS"
#define TR_MAVLINK_NO_FIX "NO Fix"
#define TR_MAVLINK_SAT "SAT"
#define TR_MAVLINK_HDOP "HDOP"
#define TR_MAVLINK_LAT "LAT"
#define TR_MAVLINK_LON "LON"
#endif
// Horus and Taranis column headers
#define TR_PHASES_HEADERS_NAME "Nome"

View file

@ -144,8 +144,6 @@
#define TR_RETA123 "RETA123LR"
#elif defined(PCBSKY9X)
#define TR_RETA123 "RETA123a"
#elif defined(CPUM2560)
#define TR_RETA123 "RETA123ab"
#else
#define TR_RETA123 "RETA123"
#endif
@ -174,11 +172,7 @@
#define TR_IRPROTOS
#endif
#if defined(CPUARM)
#define TR_XPPM
#else
#define TR_XPPM "PPM16\0""PPMsim"
#endif
#define TR_VPROTOS "PPM\0 " TR_XPPM TR_PXX TR_DSM2 TR_IRPROTOS
@ -215,27 +209,14 @@
#else
#define TR_CSWTIMER "Tim\0 "
#define TR_CSWSTICKY "Glue\0"
#if defined(CPUARM)
#define TR_CSWRANGE "Rnge\0"
#define TR_CSWSTAY "Edge\0"
#else
#define TR_CSWRANGE
#define TR_CSWSTAY
#endif
#endif
#if defined(CPUARM)
#define TR_CSWEQUAL "a=x\0 "
#else
#define TR_CSWEQUAL
#endif
#define LEN_VCSWFUNC "\005"
#if defined(CPUARM)
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""Δ}x\0 ""|Δ|}x" TR_CSWTIMER TR_CSWSTICKY
#else
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""^}x\0 ""|^|}x" TR_CSWTIMER TR_CSWSTICKY
#endif
#define LEN_VFSWFUNC "\012"
@ -313,13 +294,7 @@
#define TR_SF_RESERVE "[reserve]\0"
#if defined(CPUARM)
#define TR_VFSWFUNC TR_SF_SAFETY "Trainer\0 ""Inst. Trim""Reset\0 ""Set \0 " TR_ADJUST_GVAR "Volume\0 " "SetFailsfe" "RangeCheck" "ModuleBind" TR_SOUND TR_PLAY_TRACK TR_PLAY_VALUE TR_SF_RESERVE TR_SF_PLAY_SCRIPT TR_SF_RESERVE TR_SF_BG_MUSIC TR_VVARIO TR_HAPTIC TR_SDCLOGS "Backlight\0" TR_SF_SCREENSHOT TR_SF_TEST
#elif defined(PCBGRUVIN9X)
#define TR_VFSWFUNC TR_SF_SAFETY "Trainer\0 ""Inst. Trim""Reset\0 " TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC TR_SDCLOGS "Backlight\0" TR_SF_TEST
#else
#define TR_VFSWFUNC TR_SF_SAFETY "Trainer\0 ""Inst. Trim""Reset\0 " TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC "Backlight\0" TR_SF_TEST
#endif
#define LEN_VFSWRESET TR("\004", "\012")
@ -339,10 +314,8 @@
#if LCD_W >= 212
#define TR_FSW_RESET_TIMERS "Timer 1\0 ""Timer 2\0 ""Timer 3\0 "
#elif defined(CPUARM)
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#else
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2"
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#endif
#define TR_VFSWRESET TR(TR_FSW_RESET_TIMERS "All\0" TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC, TR_FSW_RESET_TIMERS "Vliegdata\0" TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC)
@ -357,22 +330,10 @@
#define LENGTH_UNIT_METR "m\0 "
#define SPEED_UNIT_METR "kmh"
#if defined(CPUARM)
#define LEN_VUNITSSYSTEM TR("\006", "\010")
#define TR_VUNITSSYSTEM TR("Mtrsch""Engels", "Metrisch\0 ""Engels\0 ")
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "-\0 ""V\0 ""A\0 ""mA\0""kts""m/s""f/s""kmh""mph""m\0 ""ft\0""@C\0""@F\0""%\0 ""mAh""W\0 ""mW\0""dB\0""rpm""g\0 ""@\0 ""rad""ml\0""fOz"
#else
#if defined(IMPERIAL_UNITS)
#define LENGTH_UNIT LENGTH_UNIT_IMP
#define SPEED_UNIT SPEED_UNIT_IMP
#else
#define LENGTH_UNIT LENGTH_UNIT_METR
#define SPEED_UNIT SPEED_UNIT_METR
#endif
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "V\0 ""A\0 ""m/s""-\0 " SPEED_UNIT LENGTH_UNIT "@\0 ""%\0 ""mA\0""mAh""W\0 "
#endif
#define STR_V (STR_VTELEMUNIT+1)
#define STR_A (STR_VTELEMUNIT+4)
@ -386,15 +347,10 @@
#define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "Geen\0 ""Hub\0 ""WSHHigh"
#if defined(CPUARM)
#define LEN_AMPSRC TR("\003", "\005")
#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")
#define LEN_VOLTSRC TR("\003", "\005")
#define TR_VOLTSRC TR("A1\0""A2\0""A3\0""A4\0""FAS""Cel", "A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells")
#else
#define LEN_AMPSRC TR("\003", "\005")
#define TR_AMPSRC TR("---""A1\0""A2\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""FAS\0 ""Cells")
#endif
#define LEN_VARIOSRC "\004"
#if defined(TELEMETRY_FRSKY_SPORT)
@ -403,13 +359,8 @@
#define TR_VARIOSRC "Alt\0""Alt+""VSpd""A1\0 ""A2\0"
#endif
#if defined(CPUARM)
#define LEN_VTELEMSCREENTYPE "\006"
#define TR_VTELEMSCREENTYPE "Geen\0 ""Nums\0 ""Balken""Script"
#else
#define LEN_VTELEMSCREENTYPE "\006"
#define TR_VTELEMSCREENTYPE "Nums\0 ""Balken"
#endif
#define LEN_GPSFORMAT "\004"
#define TR_GPSFORMAT "DMS\0""NMEA"
@ -445,11 +396,7 @@
#define LEN_VSWITCHES "\003"
#define LEN_VSRCRAW "\004"
#if defined(CPUARM)
#define TR_STICKS_VSRCRAW "\307Rud""\307Ele""\307Thr""\307Ail"
#else
#define TR_STICKS_VSRCRAW "Rud\0""Ele\0""Thr\0""Ail\0"
#endif
#if defined(PCBHORUS)
#define TR_TRIMS_VSRCRAW "\313Rud""\313Ele""\313Thr""\313Ail""\313T5\0""\313T6\0"
@ -485,11 +432,7 @@
#define TR_9X_3POS_SWITCHES "ID0""ID1""ID2"
#endif
#if defined(CPUARM)
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12""L13""L14""L15""L16""L17""L18""L19""L20""L21""L22""L23""L24""L25""L26""L27""L28""L29""L30""L31""L32"
#else
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12"
#endif
#if defined(PCBHORUS)
#define TR_TRIMS_SWITCHES "\313Rl""\313Rr""\313Ed""\313Eu""\313Td""\313Tu""\313Al""\313Ar""\3135d""\3135u""\3136d""\3136u"
@ -500,9 +443,6 @@
#if defined(PCBSKY9X)
#define TR_ROTARY_ENCODERS "REa\0"
#define TR_ROTENC_SWITCHES "REa"
#elif defined(PCBGRUVIN9X) || defined(PCBMEGA2560)
#define TR_ROTARY_ENCODERS "REa\0""REb\0"
#define TR_ROTENC_SWITCHES "REa""REb"
#else
#define TR_ROTARY_ENCODERS
#define TR_ROTENC_SWITCHES
@ -529,13 +469,8 @@
#define TR_CYC_VSRCRAW "[C1]""[C2]""[C3]"
#endif
#if defined(CPUARM)
#define TR_RESERVE_VSRCRAW "[--]"
#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
@ -553,14 +488,6 @@
#define LEN_VFAILSAFE TR("\013","\011")
#define TR_VFAILSAFE TR("Niet Gezet\0""Vasthouden\0""Custom\0 ""Geen Pulsen""Ontvanger\0 ","Not Set\0 ""Hold\0 ""Custom\0 ""No Pulses""Receiver\0")
#if defined(TELEMETRY_MAVLINK)
#define LEN_MAVLINK_BAUDS "\006"
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""58798 ""76800"
#define LEN_MAVLINK_AC_MODES "\011"
#define TR_MAVLINK_AC_MODES "Stabilize""Acro ""Alt Hold ""Auto ""Guided ""Loiter ""RTL ""Circle ""Pos Hold ""Land ""OF Loiter""Toy A ""Toy M ""INVALID "
#define LEN_MAVLINK_AP_MODES "\015"
#define TR_MAVLINK_AP_MODES "Manueel ""Cirkel ""Stabiliseer ""Training ""Fly by Wire A""Fly by Wire A""Auto ""RTL ""Loiter ""Begeleid ""Initialiseren""ONGELDIG "
#endif
#define LEN_VSENSORTYPES "\010"
#define TR_VSENSORTYPES "Custom\0 ""Berekend"
@ -641,13 +568,9 @@
#define TR_OUTPUT_TYPE INDENT "Output"
#endif
#define TR_PROTO TR(INDENT "Proto", INDENT "Protocol")
#if defined(CPUARM)
#define TR_PPMFRAME INDENT "PPM frame"
#define TR_REFRESHRATE TR(INDENT "Refresh", INDENT "Refresh rate")
#define STR_WARN_BATTVOLTAGE TR(INDENT "Output is VBAT: ", INDENT "Warning: output level is VBAT: ")
#else
#define TR_PPMFRAME "PPM frame"
#endif
#define TR_MS "ms"
#define TR_SWITCH TR("Schak.", "Schakelaar")
#define TR_TRIMS "Trims"
@ -774,13 +697,8 @@
#define TR_TMR1LATMINUS "Tmr1Lat min\037\124us"
#define TR_TMR1JITTERUS "Tmr1 Jitter\037\124us"
#if defined(CPUARM)
#define TR_TMIXMAXMS "Tmix max"
#define TR_FREESTACKMINB "Free Stack"
#else
#define TR_TMIXMAXMS "Tmix max\037\124ms"
#define TR_FREESTACKMINB "Free Stack\037\124b"
#endif
#define TR_MENUTORESET CENTER TR_ENTER" voor Reset"
#define TR_PPM_TRAINER "TR"
@ -826,13 +744,8 @@
#define TR_MENUFLIGHTMODE "VLIEGFASE"
#define TR_MENUHELISETUP "HELI TS-Mixer"
#if defined(CPUARM)
#define TR_MENUINPUTS "INPUTS"
#define TR_MENULIMITS "OUTPUTS"
#else
#define TR_MENUINPUTS "STICKS"
#define TR_MENULIMITS "SERVOS"
#endif
#define TR_MENUCURVES "CURVEN"
#define TR_MENUCURVE "CURVE"
@ -851,13 +764,8 @@
#define TR_MONITOR_SWITCHES "LOGISCHE SCHAKELAARS MONITOR"
#define TR_MONITOR_OUTPUT_DESC "Outputs"
#define TR_MONITOR_MIXER_DESC "Mixers"
#if defined(CPUARM)
#define TR_RECEIVER_NUM TR(INDENT "RxNum", INDENT "Receiver Nr.")
#define TR_RECEIVER INDENT "Receiver"
#else
#define TR_RECEIVER_NUM "RxNum"
#define TR_RECEIVER "RxNum"
#endif
#define TR_MULTI_RFTUNE TR(INDENT "Freq tune",INDENT "RF Freq. fine tune")
#define TR_MULTI_TELEMETRY "Telemetry"
#define TR_MULTI_VIDFREQ TR(INDENT "Vid. freq.", INDENT "Video frequency")
@ -1115,31 +1023,6 @@
#define TR_CONFIRMRESET TR("Wis Alles?", "Wis ALLE modellen en instellingen?")
#define TR_TO_MANY_LUA_SCRIPTS "Te veel Lua scripts!"
#if defined(TELEMETRY_MAVLINK)
#define TR_MAVLINK_RC_RSSI_SCALE_LABEL "Max RSSI"
#define TR_MAVLINK_PC_RSSI_EN_LABEL "PC RSSI EN"
#define TR_MAVMENUSETUP_TITLE "Mavlink setup"
#define TR_MAVLINK_BAUD_LABEL "Baudrate"
#define TR_MAVLINK_INFOS "INFOS"
#define TR_MAVLINK_MODE "MODE"
#define TR_MAVLINK_CUR_MODE "Current mode"
#define TR_MAVLINK_ARMED "Armed"
#define TR_MAVLINK_BAT_MENU_TITLE "BAT RSSI"
#define TR_MAVLINK_BATTERY_LABEL "Vliegaccu-Status"
#define TR_MAVLINK_RC_RSSI_LABEL "RC RSSI"
#define TR_MAVLINK_PC_RSSI_LABEL "PC RSSI"
#define TR_MAVLINK_NAV_MENU_TITLE "NAV"
#define TR_MAVLINK_COURSE "Course"
#define TR_MAVLINK_HEADING "Heading"
#define TR_MAVLINK_BEARING "Bearing"
#define TR_MAVLINK_ALTITUDE "Altitude"
#define TR_MAVLINK_GPS "GPS"
#define TR_MAVLINK_NO_FIX "NO Fix"
#define TR_MAVLINK_SAT "SAT"
#define TR_MAVLINK_HDOP "HDOP"
#define TR_MAVLINK_LAT "LAT"
#define TR_MAVLINK_LON "LON"
#endif
// Horus and Taranis column headers
#define TR_PHASES_HEADERS_NAME "Name"

View file

@ -141,8 +141,6 @@
#define TR_RETA123 "KWGL123LR"
#elif defined(PCBSKY9X)
#define TR_RETA123 "KWGL123a"
#elif defined(CPUM2560)
#define TR_RETA123 "KWGL123ab"
#else
#define TR_RETA123 "KWGL123"
#endif
@ -171,11 +169,7 @@
#define TR_IRPROTOS
#endif
#if defined(CPUARM)
#define TR_XPPM
#else
#define TR_XPPM "PPM16\0""PPMsim"
#endif
#define TR_VPROTOS "PPM\0 " TR_XPPM TR_PXX TR_DSM2 TR_IRPROTOS
@ -212,27 +206,14 @@
#else
#define TR_CSWTIMER "Tim\0 "
#define TR_CSWSTICKY "Stały"
#if defined(CPUARM)
#define TR_CSWRANGE "Zasię"
#define TR_CSWSTAY "Brzeg"
#else
#define TR_CSWRANGE
#define TR_CSWSTAY
#endif
#endif
#if defined(CPUARM)
#define TR_CSWEQUAL "a=x\0 "
#else
#define TR_CSWEQUAL
#endif
#define LEN_VCSWFUNC "\005"
#if defined(CPUARM)
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""Δ}x\0 ""|Δ|}x" TR_CSWTIMER TR_CSWSTICKY
#else
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""^}x\0 ""|^|}x" TR_CSWTIMER TR_CSWSTICKY
#endif
#define LEN_VFSWFUNC "\012" /*10 decimal*/
@ -310,13 +291,7 @@
#define TR_SF_RESERVE "[rezerwa]\0"
#if defined(CPUARM)
#define TR_VFSWFUNC TR_SF_SAFETY "Trener \0 ""Inst-Trim ""Resetuj\0 ""Ustaw\0 " TR_ADJUST_GVAR "Głośność\0 " "SetFailsfe" "RangeCheck" "ModuleBind" TR_SOUND TR_PLAY_TRACK TR_PLAY_VALUE TR_SF_RESERVE TR_SF_PLAY_SCRIPT TR_SF_RESERVE TR_SF_BG_MUSIC TR_VVARIO TR_HAPTIC TR_SDCLOGS "Podświetl\0" TR_SF_SCREENSHOT TR_SF_TEST
#elif defined(PCBGRUVIN9X)
#define TR_VFSWFUNC TR_SF_SAFETY "Trener \0 ""Inst-Trim ""Resetuj\0 " TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC TR_SDCLOGS "Podświetl\0" TR_SF_TEST
#else
#define TR_VFSWFUNC TR_SF_SAFETY "Trener \0 ""Inst-Trim ""Resetuj\0 " TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC "Podświetl\0" TR_SF_TEST
#endif
#define LEN_VFSWRESET TR("\004", "\011") /*9 decimal*/
@ -336,10 +311,8 @@
#if LCD_W >= 212
#define TR_FSW_RESET_TIMERS "Timer 1\0 ""Timer 2\0 ""Timer 3\0 "
#elif defined(CPUARM)
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#else
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2"
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#endif
#define TR_VFSWRESET TR(TR_FSW_RESET_TIMERS "All\0" TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC, TR_FSW_RESET_TIMERS "All\0 " TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC)
@ -349,21 +322,12 @@
#define LEN_VTELEMCHNS "\004"
#if defined(CPUARM)
#define TR_TELEM_RESERVE TR("[--]", "[---]")
#define TR_TELEM_TIME TR("Time", "Time\0")
#define TR_RAS 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_RAS
#define TR_RX_BATT
#define TR_A3_A4
#define TR_A3_A4_MIN
#endif
#define TR_ASPD_MAX TR("ASp+", "ASpd+")
@ -373,33 +337,17 @@
#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
#define LENGTH_UNIT_IMP "ft\0"
#define SPEED_UNIT_IMP "mph"
#define LENGTH_UNIT_METR "m\0 "
#define SPEED_UNIT_METR "kmh"
#if defined(CPUARM)
#define LEN_VUNITSSYSTEM TR("\006", "\010") /*8 decimal*/
#define TR_VUNITSSYSTEM TR("Metr. ""Imper.", "Metryczn""Imperial")
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "-\0 ""V\0 ""A\0 ""mA\0""kts""m/s""f/s""kmh""mph""m\0 ""ft\0""@C\0""@F\0""%\0 ""mAh""W\0 ""mW\0""dB\0""rpm""g\0 ""@\0 ""rad""ml\0""fOz"
#else
#if defined(IMPERIAL_UNITS)
#define LENGTH_UNIT LENGTH_UNIT_IMP
#define SPEED_UNIT SPEED_UNIT_IMP
#else
#define LENGTH_UNIT LENGTH_UNIT_METR
#define SPEED_UNIT SPEED_UNIT_METR
#endif
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "V\0 ""A\0 ""m/s""-\0 " SPEED_UNIT LENGTH_UNIT "@\0 ""%\0 ""mA\0""mAh""W\0 "
#endif
#define STR_V (STR_VTELEMUNIT+1)
#define STR_A (STR_VTELEMUNIT+4)
@ -413,15 +361,10 @@
#define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "None\0 ""Hub\0 ""WSHHigh"
#if defined(CPUARM)
#define LEN_AMPSRC TR("\003", "\005")
#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")
#define LEN_VOLTSRC TR("\003", "\005")
#define TR_VOLTSRC TR("A1\0""A2\0""A3\0""A4\0""FAS""Cel", "A1\0 ""A2\0 ""A3\0 ""A4\0 ""FAS\0 ""Cells")
#else
#define LEN_AMPSRC TR("\003", "\005")
#define TR_AMPSRC TR("---""A1\0""A2\0""FAS""Cel", "---\0 ""A1\0 ""A2\0 ""FAS\0 ""Cells")
#endif
#define LEN_VARIOSRC "\004"
#if defined(TELEMETRY_FRSKY_SPORT)
@ -430,13 +373,8 @@
#define TR_VARIOSRC "Wys\0""Wys+""VSpd""A1\0 ""A2\0"
#endif
#if defined(CPUARM)
#define LEN_VTELEMSCREENTYPE "\006"
#define TR_VTELEMSCREENTYPE "Brak\0 ""Liczb\0""Paski\0""Skrypt"
#else
#define LEN_VTELEMSCREENTYPE "\004"
#define TR_VTELEMSCREENTYPE "Licz""Pask"
#endif
#define LEN_GPSFORMAT "\004"
#define TR_GPSFORMAT "DMS\0""NMEA"
@ -500,11 +438,7 @@
#define TR_9X_3POS_SWITCHES "ID0""ID1""ID2"
#endif
#if defined(CPUARM)
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12""L13""L14""L15""L16""L17""L18""L19""L20""L21""L22""L23""L24""L25""L26""L27""L28""L29""L30""L31""L32"
#else
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12"
#endif
#if defined(PCBHORUS)
#define TR_TRIMS_SWITCHES "\313Rl""\313Rr""\313Ed""\313Eu""\313Td""\313Tu""\313Al""\313Ar""\3135d""\3135u""\3136d""\3136u"
@ -515,9 +449,6 @@
#if defined(PCBSKY9X)
#define TR_ROTARY_ENCODERS "REa\0"
#define TR_ROTENC_SWITCHES "REa"
#elif defined(PCBGRUVIN9X) || defined(PCBMEGA2560)
#define TR_ROTARY_ENCODERS "REa\0""REb\0"
#define TR_ROTENC_SWITCHES "REa""REb"
#else
#define TR_ROTARY_ENCODERS
#define TR_ROTENC_SWITCHES
@ -544,13 +475,8 @@
#define TR_CYC_VSRCRAW "[C1]""[C2]""[C3]"
#endif
#if defined(CPUARM)
#define TR_RESERVE_VSRCRAW "[--]"
#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""Bat\0" TR_TELEM_TIME TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_TIMERS TR_RAS "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 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
@ -568,14 +494,6 @@
#define LEN_VFAILSAFE "\011" /*9 decimal*/
#define TR_VFAILSAFE "Brak \0 ""Utrzymuj\0""Własne \0""0 sygnału""Odbiornik"
#if defined(TELEMETRY_MAVLINK)
#define LEN_MAVLINK_BAUDS "\006"
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""58798 ""76800"
#define LEN_MAVLINK_AC_MODES "\011" /*9 decimal*/
#define TR_MAVLINK_AC_MODES "Stabiliz.""Akro ""Alt Hold ""Auto ""Sterowany""Loiter ""RTL ""Koło ""Utrzymuj ""Ląduj ""OF Loiter""Toy A ""Toy M ""BŁĘDNY "
#define LEN_MAVLINK_AP_MODES "\015" /*13 decimal*/
#define TR_MAVLINK_AP_MODES "Ręczny ""Koło ""Stabilizacja ""Trening ""Fly by Wire A""Fly by Wire A""Auto ""RTL ""Loiter ""Sterowany ""Inicjalizacja""BŁĘDNY "
#endif
#define LEN_VSENSORTYPES "\012" /*10 decimal*/
#define TR_VSENSORTYPES "Użytkownik""Obliczone "
@ -640,11 +558,7 @@
#define TR_PHASENAME "Nazwa Fazy"
#define TR_MIXNAME "Nazwa Mix"
#define TR_INPUTNAME "Wpisz Nazw"
#if defined(CPUARM)
#define TR_EXPONAME "LiniaNazw"
#else
#define TR_EXPONAME "Nazwa Exp"
#endif
#define TR_BITMAP "Obrazek "
#define TR_TIMER TR("Timer", "Timer ")
#define TR_ELIMITS TR("Limi+25%", "Kanał +/- 125% ")
@ -659,13 +573,9 @@
#define TR_OUTPUT_TYPE INDENT "Wyjście"
#endif
#define TR_PROTO TR(INDENT "Proto", INDENT "Protokół")
#if defined(CPUARM)
#define TR_PPMFRAME INDENT "Ramka PPM"
#define TR_REFRESHRATE TR(INDENT "Refresh", INDENT "Refresh rate")
#define STR_WARN_BATTVOLTAGE TR(INDENT "Output is VBAT: ", INDENT "Warning: output level is VBAT: ")
#else
#define TR_PPMFRAME INDENT "Ramka PPM"
#endif
#define TR_MS "ms"
#define TR_SWITCH "Przełą"
#define TR_TRIMS "Trymy"
@ -788,13 +698,8 @@
#define TR_TMR1LATMINUS "Tmr1Lat min\037\124us"
#define TR_TMR1JITTERUS "Tmr1 Jitter\037\124us"
#if defined(CPUARM)
#define TR_TMIXMAXMS "TmixMaks"
#define TR_FREESTACKMINB "Wolny stos"
#else
#define TR_TMIXMAXMS "TmixMaks\037\124ms"
#define TR_FREESTACKMINB "Wolny stos\037\124b"
#endif
#define TR_MENUTORESET CENTER TR_ENTER " >> Reset"
#define TR_PPM_TRAINER "TR"
@ -837,13 +742,8 @@
#define TR_MENUFLIGHTMODES "FAZY LOTU"
#define TR_MENUHELISETUP "USTAW HELI"
#if defined(CPUARM)
#define TR_MENUINPUTS "WEJŚCIA"
#define TR_MENULIMITS "WYJŚCIA"
#else
#define TR_MENUINPUTS "DRĄŻKI"
#define TR_MENULIMITS "SERWA "
#endif
#define TR_MENUCURVES "KRZYWE"
#define TR_MENUCURVE "KRZYWA"
@ -862,13 +762,8 @@
#define TR_MONITOR_CHANNELS4 "CHANNELS MONITOR 25/32"
#define TR_MONITOR_OUTPUT_DESC "Outputs"
#define TR_MONITOR_MIXER_DESC "Mixers"
#if defined(CPUARM)
#define TR_RECEIVER_NUM TR( INDENT "Nr RX",INDENT "Nr odbiornika")
#define TR_RECEIVER INDENT "Receiver"
#else
#define TR_RECEIVER_NUM "NumOdb"
#define TR_RECEIVER INDENT "Receiver"
#endif
#define TR_MULTI_RFTUNE TR(INDENT "Freq tune",INDENT "RF Freq. fine tune")
#define TR_MULTI_TELEMETRY "Telemetry"
#define TR_MULTI_VIDFREQ TR(INDENT "Vid. freq.", INDENT "Video frequency")
@ -1120,31 +1015,6 @@
#define TR_CONFIRMRESET "WYkasować wszytkie modele? "
#define TR_TO_MANY_LUA_SCRIPTS "Za dużo skryptów Lua!"
#if defined(TELEMETRY_MAVLINK)
#define TR_MAVLINK_RC_RSSI_SCALE_LABEL "MaksRSSI"
#define TR_MAVLINK_PC_RSSI_EN_LABEL "PC RSSI EN"
#define TR_MAVMENUSETUP_TITLE "Ustaw.Mavlink"
#define TR_MAVLINK_BAUD_LABEL "Baudrate"
#define TR_MAVLINK_INFOS "INFO"
#define TR_MAVLINK_MODE "TRYB"
#define TR_MAVLINK_CUR_MODE "Aktualy Tryb"
#define TR_MAVLINK_ARMED "Aktywny"
#define TR_MAVLINK_BAT_MENU_TITLE "BAT RSSI"
#define TR_MAVLINK_BATTERY_LABEL "Status bateriOdbiorn."
#define TR_MAVLINK_RC_RSSI_LABEL "RC RSSI"
#define TR_MAVLINK_PC_RSSI_LABEL "PC RSSI"
#define TR_MAVLINK_NAV_MENU_TITLE "NAV"
#define TR_MAVLINK_COURSE "Kurs"
#define TR_MAVLINK_HEADING "Kierunek"
#define TR_MAVLINK_BEARING "Orientacja"
#define TR_MAVLINK_ALTITUDE "Wysokość"
#define TR_MAVLINK_GPS "GPS"
#define TR_MAVLINK_NO_FIX "NO Fix"
#define TR_MAVLINK_SAT "SAT"
#define TR_MAVLINK_HDOP "HDOP"
#define TR_MAVLINK_LAT "SZR"
#define TR_MAVLINK_LON "DLG"
#endif
// Horus and Taranis column headers
#define TR_PHASES_HEADERS_NAME "Nazwa"

View file

@ -138,8 +138,6 @@
#define TR_RETA123 "LPMA123LR"
#elif defined(PCBSKY9X)
#define TR_RETA123 "LPMA123a"
#elif defined(CPUM2560)
#define TR_RETA123 "LPMA123ab"
#else
#define TR_RETA123 "LPMA123"
#endif
@ -168,11 +166,7 @@
#define TR_IRPROTOS
#endif
#if defined(CPUARM)
#define TR_XPPM
#else
#define TR_XPPM "PPM16\0""PPMsim"
#endif
#define TR_VPROTOS "PPM\0 " TR_XPPM TR_PXX TR_DSM2 TR_IRPROTOS
@ -209,27 +203,14 @@
#else
#define TR_CSWTIMER "Tim\0 "
#define TR_CSWSTICKY "Glue\0"
#if defined(CPUARM)
#define TR_CSWRANGE "Rnge\0"
#define TR_CSWSTAY "Edge\0"
#else
#define TR_CSWRANGE
#define TR_CSWSTAY
#endif
#endif
#if defined(CPUARM)
#define TR_CSWEQUAL "a=x\0 "
#else
#define TR_CSWEQUAL
#endif
#define LEN_VCSWFUNC "\005"
#if defined(CPUARM)
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""Δ}x\0 ""|Δ|}x" TR_CSWTIMER TR_CSWSTICKY
#else
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""^}x\0 ""|^|}x" TR_CSWTIMER TR_CSWSTICKY
#endif
#define LEN_VFSWFUNC "\015"
@ -305,13 +286,7 @@
#define TR_SF_RESERVE "[reserve]\0 "
#if defined(CPUARM)
#define TR_VFSWFUNC TR_SF_SAFETY "Aprendiz\0 ""Ajuste Rapido""Reset\0 ""Set \0 " TR_ADJUST_GVAR "Volume\0 " "SetFailsafe\0 " "RangeCheck\0 " "ModuleBind\0 " TR_SOUND TR_PLAY_TRACK TR_PLAY_VALUE TR_SF_RESERVE TR_SF_PLAY_SCRIPT TR_SF_RESERVE TR_SF_BG_MUSIC TR_VVARIO TR_HAPTIC TR_SDCLOGS "Backlight\0 " TR_SF_SCREENSHOT TR_SF_TEST
#elif defined(PCBGRUVIN9X)
#define TR_VFSWFUNC TR_SF_SAFETY "Aprendiz\0 ""Ajuste Rapido""Reset\0 " TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC TR_SDCLOGS "Backlight\0 " TR_SF_TEST
#else
#define TR_VFSWFUNC TR_SF_SAFETY "Aprendiz\0 ""Ajuste Rapido""Reset\0 " TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE "Backlight\0 " TR_SF_TEST
#endif
#define LEN_VFSWRESET TR("\004", "\011")
@ -331,10 +306,8 @@
#if defined(PCBTARANIS)
#define TR_FSW_RESET_TIMERS "Timer 1\0 ""Timer 2\0 ""Timer 3\0 "
#elif defined(CPUARM)
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#else
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2"
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#endif
#define TR_VFSWRESET TR(TR_FSW_RESET_TIMERS "All\0" TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC, TR_FSW_RESET_TIMERS "All\0 " TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC)
@ -344,21 +317,12 @@
#define LEN_VTELEMCHNS "\004"
#if defined(CPUARM)
#define TR_TELEM_RESERVE TR("[--]", "[---]")
#define TR_TELEM_TIME TR("Time", "Time\0")
#define TR_RAS 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_RAS
#define TR_RX_BATT
#define TR_A3_A4
#define TR_A3_A4_MIN
#endif
#define TR_ASPD_MAX TR("ASp+", "ASpd+")
@ -368,33 +332,17 @@
#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
#define LENGTH_UNIT_IMP "ft\0"
#define SPEED_UNIT_IMP "mph"
#define LENGTH_UNIT_METR "m\0 "
#define SPEED_UNIT_METR "kmh"
#if defined(CPUARM)
#define LEN_VUNITSSYSTEM TR("\006", "\010")
#define TR_VUNITSSYSTEM TR("Metric""Imper.", "Metric\0 ""Imperial")
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "-\0 ""V\0 ""A\0 ""mA\0""kts""m/s""f/s""kmh""mph""m\0 ""ft\0""@C\0""@F\0""%\0 ""mAh""W\0 ""mW\0""dB\0""rpm""g\0 ""@\0 ""rad""ml\0""fOz"
#else
#if defined(IMPERIAL_UNITS)
#define LENGTH_UNIT LENGTH_UNIT_IMP
#define SPEED_UNIT SPEED_UNIT_IMP
#else
#define LENGTH_UNIT LENGTH_UNIT_METR
#define SPEED_UNIT SPEED_UNIT_METR
#endif
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "V\0 ""A\0 ""m/s""-\0 " SPEED_UNIT LENGTH_UNIT "@\0 ""%\0 ""mA\0""mAh""W\0 "
#endif
#define STR_V (STR_VTELEMUNIT+1)
#define STR_A (STR_VTELEMUNIT+4)
@ -408,15 +356,10 @@
#define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "Nada\0 ""Hub\0 ""WSHHigh"
#if defined(CPUARM)
#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("A1\0""A2\0""A3\0""A4\0""FAS""Cel", "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"
#if defined(TELEMETRY_FRSKY_SPORT)
@ -490,11 +433,7 @@
#define TR_9X_3POS_SWITCHES "ID0""ID1""ID2"
#endif
#if defined(CPUARM)
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12""L13""L14""L15""L16""L17""L18""L19""L20""L21""L22""L23""L24""L25""L26""L27""L28""L29""L30""L31""L32"
#else
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12"
#endif
#if defined(PCBHORUS)
#define TR_TRIMS_SWITCHES "\313Rl""\313Rr""\313Ed""\313Eu""\313Td""\313Tu""\313Al""\313Ar""\3135d""\3135u""\3136d""\3136u"
@ -505,9 +444,6 @@
#if defined(PCBSKY9X)
#define TR_ROTARY_ENCODERS "REa\0"
#define TR_ROTENC_SWITCHES "REa"
#elif defined(PCBGRUVIN9X) || defined(PCBMEGA2560)
#define TR_ROTARY_ENCODERS "REa\0""REb\0"
#define TR_ROTENC_SWITCHES "REa""REb"
#else
#define TR_ROTARY_ENCODERS
#define TR_ROTENC_SWITCHES
@ -534,13 +470,8 @@
#define TR_CYC_VSRCRAW "[C1]""[C2]""[C3]"
#endif
#if defined(CPUARM)
#define TR_RESERVE_VSRCRAW "[--]"
#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
@ -558,14 +489,6 @@
#define LEN_VFAILSAFE "\011"
#define TR_VFAILSAFE "Not set\0 ""Hold\0 ""Custom\0 ""No pulses""Receiver\0"
#if defined(TELEMETRY_MAVLINK)
#define LEN_MAVLINK_BAUDS "\006"
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""58798 ""76800"
#define LEN_MAVLINK_AC_MODES "\011"
#define TR_MAVLINK_AC_MODES "Stabilize""Acro ""Alt Hold ""Auto ""Guided ""Loiter ""RTL ""Circle ""Pos Hold ""Land ""OF Loiter""Toy A ""Toy M ""INVALID "
#define LEN_MAVLINK_AP_MODES "\015"
#define TR_MAVLINK_AP_MODES "Manual ""Circle ""Stabilize ""Training ""Fly by Wire A""Fly by Wire A""Auto ""RTL ""Loiter ""Guided ""Initialising ""INVALID "
#endif
#define LEN_VSENSORTYPES "\012"
#define TR_VSENSORTYPES "Custom\0 ""Calculated"
@ -770,13 +693,8 @@
#define TR_TMR1LATMINUS "Tmr1Lat min\037\124us"
#define TR_TMR1JITTERUS "Tmr1 Jitter\037\124us"
#if defined(CPUARM)
#define TR_TMIXMAXMS "Tmix max"
#define TR_FREESTACKMINB "Free Stack"
#else
#define TR_TMIXMAXMS "Tmix max\037\124ms"
#define TR_FREESTACKMINB "Pilha Livre\037\124b"
#endif
#define TR_MENUTORESET CENTER TR_ENTER" Reinicia"
#define TR_PPM_TRAINER "TR"
@ -1100,31 +1018,6 @@
#define TR_CONFIRMRESET "Erase ALL models and settings?"
#define TR_TO_MANY_LUA_SCRIPTS "Too many Lua scripts!"
#if defined(TELEMETRY_MAVLINK)
#define TR_MAVLINK_RC_RSSI_SCALE_LABEL "Max RSSI"
#define TR_MAVLINK_PC_RSSI_EN_LABEL "PC RSSI EN"
#define TR_MAVMENUSETUP_TITLE "Mavlink Setup"
#define TR_MAVLINK_BAUD_LABEL "Baudrate"
#define TR_MAVLINK_INFOS "INFOS"
#define TR_MAVLINK_MODE "MODE"
#define TR_MAVLINK_CUR_MODE "Current Mode"
#define TR_MAVLINK_ARMED "Armed"
#define TR_MAVLINK_BAT_MENU_TITLE "BAT RSSI"
#define TR_MAVLINK_BATTERY_LABEL "Flight Battery status"
#define TR_MAVLINK_RC_RSSI_LABEL "RC RSSI"
#define TR_MAVLINK_PC_RSSI_LABEL "PC RSSI"
#define TR_MAVLINK_NAV_MENU_TITLE "NAV"
#define TR_MAVLINK_COURSE "Course"
#define TR_MAVLINK_HEADING "Heading"
#define TR_MAVLINK_BEARING "Bearing"
#define TR_MAVLINK_ALTITUDE "Altitude"
#define TR_MAVLINK_GPS "GPS"
#define TR_MAVLINK_NO_FIX "NO Fix"
#define TR_MAVLINK_SAT "SAT"
#define TR_MAVLINK_HDOP "HDOP"
#define TR_MAVLINK_LAT "LAT"
#define TR_MAVLINK_LON "LON"
#endif
// Horus and Taranis column headers
#define TR_PHASES_HEADERS_NAME "Name"

View file

@ -137,8 +137,6 @@
#define TR_RETA123 "RHGS123HV"
#elif defined(PCBSKY9X)
#define TR_RETA123 "RHGS123a"
#elif defined(CPUM2560)
#define TR_RETA123 "RHGS123ab"
#else
#define TR_RETA123 "RHGS123"
#endif
@ -167,12 +165,6 @@
#define TR_IRPROTOS
#endif
#if defined(CPUARM)
#define TR_XPPM
#else
#define TR_XPPM "PPM16\0""PPMsim"
#endif
#define TR_VPROTOS "PPM\0 " TR_XPPM TR_PXX TR_DSM2 TR_IRPROTOS
#define LEN_POSNEG "\003"
@ -208,27 +200,14 @@
#else
#define TR_CSWTIMER "Tim\0 "
#define TR_CSWSTICKY "Seg\0 "
#if defined(CPUARM)
#define TR_CSWRANGE "Vidd\0"
#define TR_CSWSTAY "Kant\0"
#else
#define TR_CSWRANGE
#define TR_CSWSTAY
#endif
#endif
#if defined(CPUARM)
#define TR_CSWEQUAL "a=x\0 "
#else
#define TR_CSWEQUAL
#endif
#define LEN_VCSWFUNC "\005"
#if defined(CPUARM)
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""Δ}x\0 ""|Δ|}x" TR_CSWTIMER TR_CSWSTICKY
#else
#define TR_VCSWFUNC "---\0 " TR_CSWEQUAL "a~x\0 ""a>x\0 ""a<x\0 " TR_CSWRANGE "|a|>x""|a|<x""AND\0 ""OR\0 ""XOR\0 " TR_CSWSTAY "a=b\0 ""a>b\0 ""a<b\0 ""^}x\0 ""|^|}x" TR_CSWTIMER TR_CSWSTICKY
#endif
#define LEN_VFSWFUNC "\012"
@ -306,13 +285,7 @@
#define TR_SF_RESERVE "[reserve]\0"
#if defined(CPUARM)
#define TR_VFSWFUNC TR_SF_SAFETY "Trainer\0 ""Sätt Trim\0""Nollställ\0""Sätt\0 " TR_ADJUST_GVAR "Volym\0 " "SetFailsfe" "RangeCheck" "ModuleBind" TR_SOUND TR_PLAY_TRACK TR_PLAY_VALUE TR_SF_RESERVE TR_SF_PLAY_SCRIPT TR_SF_RESERVE TR_SF_BG_MUSIC TR_VVARIO TR_HAPTIC TR_SDCLOGS "Belysning\0" TR_SF_SCREENSHOT TR_SF_TEST
#elif defined(PCBGRUVIN9X)
#define TR_VFSWFUNC TR_SF_SAFETY "Trainer \0 ""Sätt Trim\0""Nollställ\0" TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC TR_SDCLOGS "Belysning\0" TR_SF_TEST
#else
#define TR_VFSWFUNC TR_SF_SAFETY "Trainer \0 ""Sätt Trim\0""Nollställ\0" TR_ADJUST_GVAR TR_SOUND TR_PLAY_TRACK TR_PLAY_BOTH TR_PLAY_VALUE TR_VVARIO TR_HAPTIC "Belysning\0" TR_SF_TEST
#endif
#define LEN_VFSWRESET TR("\004", "\011")
@ -332,10 +305,8 @@
#if defined(PCBTARANIS)
#define TR_FSW_RESET_TIMERS "Timer 1\0 ""Timer 2\0 ""Timer 3\0 "
#elif defined(CPUARM)
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#else
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2"
#define TR_FSW_RESET_TIMERS "Tmr1""Tmr2""Tmr3"
#endif
#define TR_VFSWRESET TR(TR_FSW_RESET_TIMERS "All\0" TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC, TR_FSW_RESET_TIMERS "Alla\0 " TR_FSW_RESET_TELEM TR_FSW_RESET_ROTENC)
@ -345,21 +316,12 @@
#define LEN_VTELEMCHNS "\004"
#if defined(CPUARM)
#define TR_TELEM_RESERVE TR("[--]", "[---]")
#define TR_TELEM_TIME TR("Tid\0", "Tid\0 ")
#define TR_RAS 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_RAS
#define TR_RX_BATT
#define TR_A3_A4
#define TR_A3_A4_MIN
#endif
#define TR_ASPD_MAX TR("ASp+", "ASpd+")
@ -369,33 +331,17 @@
#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
#define LENGTH_UNIT_IMP "fot"
#define SPEED_UNIT_IMP "mph"
#define LENGTH_UNIT_METR "m\0 "
#define SPEED_UNIT_METR "kmh"
#if defined(CPUARM)
#define LEN_VUNITSSYSTEM TR("\006", "\010")
#define TR_VUNITSSYSTEM TR("Metri.""Imper.", "Metriska""Imperial")
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "-\0 ""V\0 ""A\0 ""mA\0""kts""m/s""f/s""kmh""mph""m\0 ""ft\0""@C\0""@F\0""%\0 ""mAh""W\0 ""mW\0""dB\0""rpm""g\0 ""@\0 ""rad""ml\0""fOz"
#else
#if defined(IMPERIAL_UNITS)
#define LENGTH_UNIT LENGTH_UNIT_IMP
#define SPEED_UNIT SPEED_UNIT_IMP
#else
#define LENGTH_UNIT LENGTH_UNIT_METR
#define SPEED_UNIT SPEED_UNIT_METR
#endif
#define LEN_VTELEMUNIT "\003"
#define TR_VTELEMUNIT "V\0 ""A\0 ""m/s""-\0 " SPEED_UNIT LENGTH_UNIT "@\0 ""%\0 ""mA\0""mAh""W\0 "
#endif
#define STR_V (STR_VTELEMUNIT+1)
#define STR_A (STR_VTELEMUNIT+4)
@ -409,15 +355,10 @@
#define LEN_VTELPROTO "\007"
#define TR_VTELPROTO "---\0 ""Hub\0 ""WSHHög."
#if defined(CPUARM)
#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("A1\0""A2\0""A3\0""A4\0""FAS""Cel", "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"
#if defined(TELEMETRY_FRSKY_SPORT)
@ -426,13 +367,8 @@
#define TR_VARIOSRC "Alti\0""Alti+""Vario""A1\0 ""A2\0"
#endif
#if defined(CPUARM)
#define LEN_VTELEMSCREENTYPE "\007"
#define TR_VTELEMSCREENTYPE "Inget\0 ""Siffror""Staplar""Script\0"
#else
#define LEN_VTELEMSCREENTYPE "\007"
#define TR_VTELEMSCREENTYPE "Siffror""Staplar"
#endif
#define LEN_GPSFORMAT "\004"
#define TR_GPSFORMAT "HMS NMEA"
@ -505,11 +441,7 @@
#define TR_9X_3POS_SWITCHES "ID0""ID1""ID2"
#endif
#if defined(CPUARM)
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12""L13""L14""L15""L16""L17""L18""L19""L20""L21""L22""L23""L24""L25""L26""L27""L28""L29""L30""L31""L32"
#else
#define TR_LOGICALSW "L01""L02""L03""L04""L05""L06""L07""L08""L09""L10""L11""L12"
#endif
#if defined(PCBHORUS)
#define TR_TRIMS_SWITCHES "\313Rv""\313Rh""\313Hn""\313Hu""\313Gn""\313Gu""\313Sv""\313Sh""\3135d""\3135u""\3136d""\3136u"
@ -520,9 +452,6 @@
#if defined(PCBSKY9X)
#define TR_ROTARY_ENCODERS "REa\0"
#define TR_ROTENC_SWITCHES "REa"
#elif defined(PCBGRUVIN9X) || defined(PCBMEGA2560)
#define TR_ROTARY_ENCODERS "REa\0""REb\0"
#define TR_ROTENC_SWITCHES "REa""REb"
#else
#define TR_ROTARY_ENCODERS
#define TR_ROTENC_SWITCHES
@ -551,13 +480,8 @@
#define TR_CYC_VSRCRAW "[C1]""[C2]""[C3]"
#endif
#if defined(CPUARM)
#define TR_RESERVE_VSRCRAW "[--]"
#define TR_EXTRA_VSRCRAW "Batt""Tid\0""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" TR_TELEM_TIME TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_RESERVE TR_TELEM_TIMERS TR_RAS "Tx\0 ""Rx\0 " 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""Tid\0"
#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
@ -575,14 +499,6 @@
#define LEN_VFAILSAFE "\011"
#define TR_VFAILSAFE "Ej givet\0""Lås Servo""Anpassat\0""Pulsfritt""Mottagare"
#if defined(TELEMETRY_MAVLINK)
#define LEN_MAVLINK_BAUDS "\006"
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""58798 ""76800"
#define LEN_MAVLINK_AC_MODES "\011"
#define TR_MAVLINK_AC_MODES "Stabil ""Akrobat ""Lås Höjd ""Automat ""Guidad ""Hovra ""Flyg Hem ""Cirkla ""Håll Pos.""Landa ""OF Hovra ""Leksak A ""Leksak M ""OGILTIG "
#define LEN_MAVLINK_AP_MODES "\015"
#define TR_MAVLINK_AP_MODES "Manuell ""Cirkla ""Stabilisera ""Övning ""Fly by Wire A""Fly by Wire A""Automatisk ""Flyg Hem ""Hovra ""Guidad ""Initialiserar""OGILTIG "
#endif
#define LEN_VSENSORTYPES "\010"
#define TR_VSENSORTYPES "Egen\0 ""Beräknad"
@ -666,13 +582,9 @@
#define TR_OUTPUT_TYPE INDENT "Output"
#endif
#define TR_PROTO TR(INDENT "Proto", INDENT "Protokoll")
#if defined(CPUARM)
#define TR_PPMFRAME INDENT "PPM-paket"
#define TR_REFRESHRATE TR(INDENT "Refresh", INDENT "Refresh rate")
#define STR_WARN_BATTVOLTAGE TR(INDENT "Output is VBAT: ", INDENT "Warning: output level is VBAT: ")
#else
#define TR_PPMFRAME "PPM-paket"
#endif
#define TR_MS "ms"
#define TR_SWITCH "Brytare"
#define TR_TRIMS "Trimmar"
@ -795,13 +707,8 @@
#define TR_TMR1LATMINUS "Tmr1Lat min\037\124us"
#define TR_TMR1JITTERUS "Tmr1 Jitter\037\124us"
#if defined(CPUARM)
#define TR_TMIXMAXMS "Tmix max"
#define TR_FREESTACKMINB "Free Stack"
#else
#define TR_TMIXMAXMS "Tmix max\037\124ms"
#define TR_FREESTACKMINB "Free Stack\037\124b"
#endif
#define TR_MENUTORESET CENTER TR_ENTER " Nollar"
#define TR_PPM_TRAINER "TR"
@ -844,13 +751,8 @@
#define TR_MENUFLIGHTMODES "FLYGLÄGEN"
#define TR_MENUHELISETUP "HELIKOPTER"
#if defined(CPUARM)
#define TR_MENUINPUTS "INPUT"
#define TR_MENULIMITS "SERVON"
#else
#define TR_MENUINPUTS "SPAKAR"
#define TR_MENULIMITS "SERVON"
#endif
#define TR_MENUCURVES "KURVOR"
#define TR_MENUCURVE "KURVA"
@ -869,13 +771,8 @@
#define TR_MONITOR_CHANNELS4 "CHANNELS MONITOR 25/32"
#define TR_MONITOR_OUTPUT_DESC "Outputs"
#define TR_MONITOR_MIXER_DESC "Mixers"
#if defined(CPUARM)
#define TR_RECEIVER_NUM TR(INDENT "RxNum", INDENT "Mottagare Nr.")
#define TR_RECEIVER INDENT "Receiver"
#else
#define TR_RECEIVER_NUM "RxNum"
#define TR_RECEIVER "RxNum"
#endif
#define TR_SYNCMENU "Synk [MENU]"
#define TR_MULTI_RFTUNE TR(INDENT "Freq tune",INDENT "RF Freq. fine tune")
#define TR_MULTI_TELEMETRY "Telemetry"
@ -1128,31 +1025,6 @@
#define TR_CONFIRMRESET "Erase ALL models and settings?"
#define TR_TO_MANY_LUA_SCRIPTS "För många Lua-scripts!"
#if defined(TELEMETRY_MAVLINK)
#define TR_MAVLINK_RC_RSSI_SCALE_LABEL "Max RSSI"
#define TR_MAVLINK_PC_RSSI_EN_LABEL "PC RSSI EN"
#define TR_MAVMENUSETUP_TITLE "MAVLINKINSTÄLLNINGAR"
#define TR_MAVLINK_BAUD_LABEL "Baudrate"
#define TR_MAVLINK_INFOS "INFOS"
#define TR_MAVLINK_MODE "LÄGE"
#define TR_MAVLINK_CUR_MODE "Nuvarande Läge"
#define TR_MAVLINK_ARMED "Osäkrad"
#define TR_MAVLINK_BAT_MENU_TITLE "BAT RSSI"
#define TR_MAVLINK_BATTERY_LABEL "Status för flygbatteri"
#define TR_MAVLINK_RC_RSSI_LABEL "RC RSSI"
#define TR_MAVLINK_PC_RSSI_LABEL "PC RSSI"
#define TR_MAVLINK_NAV_MENU_TITLE "NAV"
#define TR_MAVLINK_COURSE "Kurs"
#define TR_MAVLINK_HEADING "Riktning"
#define TR_MAVLINK_BEARING "Bäring"
#define TR_MAVLINK_ALTITUDE "Höjd"
#define TR_MAVLINK_GPS "GPS"
#define TR_MAVLINK_NO_FIX "EJ Lås"
#define TR_MAVLINK_SAT "SAT"
#define TR_MAVLINK_HDOP "HDOP"
#define TR_MAVLINK_LAT "LAT"
#define TR_MAVLINK_LON "LON"
#endif
// Horus and Taranis column headers
#define TR_PHASES_HEADERS_NAME "Namn"

View file

@ -21,172 +21,7 @@ tts_languages = {
"de",
"pt"
}
tts_avr = {
"tts%s" % language: ("TTS", language.upper(), None) for language in tts_languages
}
options_9x_ext = {
"nmea": ("TELEMETRY", "NMEA", None),
"frsky": ("TELEMETRY", "FRSKY", None),
"telemetrez": ("TELEMETRY", "TELEMETREZ", None),
"jeti": ("TELEMETRY", "JETI", None),
"ardupilot": ("TELEMETRY", "ARDUPILOT", None),
"mavlink": ("TELEMETRY", "MAVLINK", None),
}
options_9x = {
"heli": ("HELI", "YES", "NO"),
"templates": ("TEMPLATES", "YES", "NO"),
"nosplash": ("SPLASH", "NO", "YES"),
"nofp": ("FLIGHT_MODES", "NO", "YES"),
"nocurves": ("CURVES", "NO", "YES"),
"audio": ("AUDIO", "YES", "NO"),
"voice": ("VOICE", "YES", "NO"),
"haptic": ("HAPTIC", "YES", "NO"),
"pwmbl": ("PWM_BACKLIGHT", "YES", "NO"),
"turnigyfix": ("TURNIGY_TRANSMITTER_FIX", "YES", "NO"),
"acurStats": ("ACCURAT_THROTTLE_STATS", "YES", "NO"),
"arithOvfl": ("ARITHMETIC_OVERFLOW_CHECK", "YES", "NO"),
# "PXX": ("PXX", "YES", "NO"),
"DSM2": ("DSM2", "PPM ", "NO"),
"potscroll": ("NAVIGATION", "POTS ", "NO"),
"rotenc": ("NAVIGATION", "ROTENC ", "NO"),
"sp22": ("SP22", "YES", "NO"),
"autosource": ("AUTOSOURCE", "YES", "NO"),
"autoswitch": ("AUTOSWITCH", "YES", "NO"),
"dblkeys": ("DBLKEYS", "YES", "NO"),
"ppmca": ("PPM_CENTER_ADJUSTABLE", "YES", "NO"),
"ppmus": ("PPM_UNIT", "US", "PERCENT_PREC1"),
"gvars": ("GVARS", "YES", "NO"),
"symlimits": ("PPM_LIMITS_SYMETRICAL", "YES", "NO"),
"nographics": ("GRAPHICS", "NO", "YES"),
"battgraph": ("BATTGRAPH", "YES", "NO"),
"nobold": ("BOLD", "NO", "YES"),
"sqt5font": ("FONT", "SQT5 ", None),
"thrtrace": ("THR_TRACE", "YES", "NO"),
"pgbar": ("EEPROM_PROGRESS_BAR", "YES", "NO"),
"imperial": ("UNITS", "IMPERIAL", "METRIC"),
"nogps": ("GPS", "NO", "YES"),
"nogauges": ("GAUGES", "NO", "YES"),
"novario": ("VARIO", "NO", "YES"),
"nowshh": ("WS_HOW_HIGH", "NO", "YES"),
"faimode": ("FAI", "YES", None),
"faichoice": ("FAI", "CHOICE ", None),
"fasoffset": ("FAS_OFFSET", "YES", "NO"),
"nooverridech": ("OVERRIDE_CHANNEL_FUNCTION", "NO", "YES"),
"stickrev": ("FRSKY_STICKS", "YES", "NO")
}
options_9x.update(options_9x_ext)
options_9x.update(tts_avr)
options_9x128 = {
"heli": ("HELI", "YES", "NO"),
"templates": ("TEMPLATES", "YES", "NO"),
"nosplash": ("SPLASH", "NO", "YES"),
"nofp": ("FLIGHT_MODES", "NO", "YES"),
"nocurves": ("CURVES", "NO", "YES"),
"audio": ("AUDIO", "YES", "NO"),
"voice": ("VOICE", "YES", "NO"),
"haptic": ("HAPTIC", "YES", "NO"),
"pwmbl": ("PWM_BACKLIGHT", "YES", "NO"),
"turnigyfix": ("TURNIGY_TRANSMITTER_FIX", "YES", "NO"),
# "PXX": ("PXX", "YES", "NO"),
"DSM2": ("DSM2", "PPM", "NO"),
"potscroll": ("NAVIGATION", "POTS", "NO"),
"rotenc": ("NAVIGATION", "ROTENC", "NO"),
"sp22": ("SP22", "YES", "NO"),
"autosource": ("AUTOSOURCE", "YES", "NO"),
"autoswitch": ("AUTOSWITCH", "YES", "NO"),
"dblkeys": ("DBLKEYS", "YES", "NO"),
"ppmca": ("PPM_CENTER_ADJUSTABLE", "YES", "NO"),
"ppmus": ("PPM_UNIT", "US", "PERCENT_PREC1"),
"gvars": ("GVARS", "YES", "NO"),
"symlimits": ("PPM_LIMITS_SYMETRICAL", "YES", "NO"),
"nographics": ("GRAPHICS", "NO", "YES"),
"battgraph": ("BATTGRAPH", "YES", "NO"),
"nobold": ("BOLD", "NO", "YES"),
"sqt5font": ("FONT", "SQT5", None),
"thrtrace": ("THR_TRACE", "YES", "NO"),
"pgbar": ("EEPROM_PROGRESS_BAR", "YES", "NO"),
"imperial": ("UNITS", "IMPERIAL", "METRIC"),
"nogps": ("GPS", "NO", "YES"),
"nogauges": ("GAUGES", "NO", "YES"),
"novario": ("VARIO", "NO", "YES"),
"nowshh": ("WS_HOW_HIGH", "NO", "YES"),
"faimode": ("FAI", "YES", None),
"faichoice": ("FAI", "CHOICE", None),
"nooverridech": ("OVERRIDE_CHANNEL_FUNCTION", "NO", "YES")
}
options_9x128.update(options_9x_ext)
options_9x128.update(tts_avr)
options_gruvin9x = {
"heli": ("HELI", "YES", "NO"),
"templates": ("TEMPLATES", "YES", "NO"),
"nocurves": ("CURVES", "NO", "YES"),
"nofp": ("FLIGHT_MODES", "NO", "YES"),
"sdcard": ("SDCARD", "YES", "NO"),
"voice": ("VOICE", "YES", "NO"),
"PXX": ("PXX", "YES", "NO"),
"DSM2": ("DSM2", "SERIAL", "NO"),
"DSM2PPM": ("DSM2", "PPM", "NO"),
"potscroll": ("NAVIGATION", "POTS", "NO"),
"ppmca": ("PPM_CENTER_ADJUSTABLE", "YES", "NO"),
"ppmus": ("PPM_UNIT", "US", "PERCENT_PREC1"),
"gvars": ("GVARS", "YES", "NO"),
"symlimits": ("PPM_LIMITS_SYMETRICAL", "YES", "NO"),
"autosource": ("AUTOSOURCE", "YES", "NO"),
"autoswitch": ("AUTOSWITCH", "YES", "NO"),
"dblkeys": ("DBLKEYS", "YES", "NO"),
"nographics": ("GRAPHICS", "NO", "YES"),
"battgraph": ("BATTGRAPH", "YES", "NO"),
"nobold": ("BOLD", "NO", "YES"),
"sqt5font": ("FONT", "SQT5", None),
"pgbar": ("EEPROM_PROGRESS_BAR", "YES", "NO"),
"imperial": ("UNITS", "IMPERIAL", "METRIC"),
"faimode": ("FAI", "YES", None),
"faichoice": ("FAI", "CHOICE", None),
"nooverridech": ("OVERRIDE_CHANNEL_FUNCTION", "NO", "YES")
}
options_gruvin9x.update(tts_avr)
options_mega2560 = {
"heli": ("HELI", "YES", "NO"),
"templates": ("TEMPLATES", "YES", "NO"),
"nofp": ("FLIGHT_MODES", "NO", "YES"),
"nocurves": ("CURVES", "NO", "YES"),
"PWR": ("PWRMANAGE", "YES", "NO"),
"sdcard": ("SDCARD", "YES", "NO"),
"voice": ("VOICE", "YES", "NO"),
"PXX": ("PXX", "YES", "NO"),
"DSM2": ("DSM2", "SERIAL", "NO"),
"DSM2PPM": ("DSM2", "PPM", "NO"),
"ST7565R": ("LCD", "ST7565R", None),
"ERC12864FSF": ("LCD", "ERC12864FSF", None),
"ST7920": ("LCD", "ST7920", None),
"potscroll": ("NAVIGATION", "POTS", "NO"),
"ppmca": ("PPM_CENTER_ADJUSTABLE", "YES", "NO"),
"ppmus": ("PPM_UNIT", "US", "PERCENT_PREC1"),
"gvars": ("GVARS", "YES", "NO"),
"symlimits": ("PPM_LIMITS_SYMETRICAL", "YES", "NO"),
"autosource": ("AUTOSOURCE", "YES", "NO"),
"autoswitch": ("AUTOSWITCH", "YES", "NO"),
"dblkeys": ("DBLKEYS", "YES", "NO"),
"nographics": ("GRAPHICS", "NO", "YES"),
"battgraph": ("BATTGRAPH", "YES", "NO"),
"nobold": ("BOLD", "NO", "YES"),
"sqt5font": ("FONT", "SQT5", None),
"pgbar": ("EEPROM_PROGRESS_BAR", "YES", "NO"),
"imperial": ("UNITS", "IMPERIAL", "METRIC"),
"faimode": ("FAI", "YES", None),
"faichoice": ("FAI", "CHOICE", None),
"nooverridech": ("OVERRIDE_CHANNEL_FUNCTION", "NO", "YES")
}
options_mega2560.update(tts_avr)
options_sky9x = {
"heli": ("HELI", "YES", "NO"),