mirror of
https://github.com/opentx/opentx.git
synced 2025-07-16 12:55:12 +03:00
3djc/telem rename (#3678)
* Rename EXT option to TELEMETRY * Change test accordingly * Rename FRSKY to TELEMETRY_FRSKY * Rename ARDUPILOT to TELEMETRY_ARDUPILOT * More renames (JETI, MAVLINK, NMEA) * Fixes to make commit-test happy * Further tests added to commit-test * Cleanup * Rename EXTSTD to TELEMETRY_NONE
This commit is contained in:
parent
0b67d412a0
commit
52435703a0
62 changed files with 203 additions and 198 deletions
|
@ -19,7 +19,7 @@
|
|||
|
||||
#define SIMU
|
||||
#define SIMU_EXCEPTIONS
|
||||
#define FRSKY
|
||||
#define TELEMETRY_FRSKY
|
||||
#define PHASES
|
||||
#undef min
|
||||
#undef max
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#define PCBSKY9X
|
||||
#define PCBSKY
|
||||
#define STAMP
|
||||
#define FRSKY
|
||||
#define TELEMETRY_FRSKY
|
||||
#define FRSKY_HUB
|
||||
#define WS_HOW_HIGH
|
||||
#define TEMPLATES
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
|
||||
#ifdef INIT_IMPORT
|
||||
#undef INIT_IMPORT
|
||||
#ifdef FRSKY
|
||||
#ifdef TELEMETRY_FRSKY
|
||||
telemetryStreaming = 20;
|
||||
#endif
|
||||
#endif
|
||||
|
|
|
@ -439,7 +439,7 @@ enum TelemetrySource {
|
|||
TELEM_GPS_TIME,
|
||||
TELEM_CSW_MAX = TELEM_MAX_POWER,
|
||||
TELEM_NOUSR_MAX = TELEM_A2,
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
TELEM_DISPLAY_MAX = TELEM_MAX_POWER,
|
||||
#else
|
||||
TELEM_DISPLAY_MAX = TELEM_TIMER2, // because used also in PlayValue
|
||||
|
@ -452,9 +452,9 @@ enum TelemetrySource {
|
|||
#define NUM_TELEMETRY TELEM_CSW_MAX
|
||||
#elif defined(WS_HOW_HIGH)
|
||||
#define NUM_TELEMETRY TELEM_ALT
|
||||
#elif defined(FRSKY)
|
||||
#elif defined(TELEMETRY_FRSKY)
|
||||
#define NUM_TELEMETRY TELEM_A2
|
||||
#elif defined(MAVLINK)
|
||||
#elif defined(TELEMETRY_MAVLINK)
|
||||
#define NUM_TELEMETRY 4
|
||||
#else
|
||||
#define NUM_TELEMETRY TELEM_TIMER2
|
||||
|
@ -1018,7 +1018,7 @@ enum ResetFunctionParam {
|
|||
FUNC_RESET_TIMER3,
|
||||
#endif
|
||||
FUNC_RESET_FLIGHT,
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
FUNC_RESET_TELEMETRY,
|
||||
#endif
|
||||
#if ROTARY_ENCODERS > 0
|
||||
|
|
|
@ -604,7 +604,7 @@ PACK(struct FrSkyTelemetryData {
|
|||
* MAVLINK Telemetry structure
|
||||
*/
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
PACK(struct MavlinkTelemetryData {
|
||||
uint8_t rc_rssi_scale:4;
|
||||
uint8_t pc_rssi_en:1;
|
||||
|
@ -758,9 +758,9 @@ typedef uint8_t swarnenable_t;
|
|||
#define MODEL_GVARS_DATA GVarData gvars[MAX_GVARS];
|
||||
#endif
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
#define TELEMETRY_DATA MavlinkTelemetryData mavlink;
|
||||
#elif defined(FRSKY) || !defined(PCBSTD)
|
||||
#elif defined(TELEMETRY_FRSKY) || !defined(PCBSTD)
|
||||
#define TELEMETRY_DATA NOBACKUP(FrSkyTelemetryData frsky);
|
||||
#else
|
||||
#define TELEMETRY_DATA
|
||||
|
|
|
@ -36,7 +36,7 @@ void loadFontCache();
|
|||
extern const pm_uchar font_5x7[];
|
||||
extern const pm_uchar font_10x14[];
|
||||
|
||||
#if defined(BOLD_FONT) && (!defined(CPUM64) || defined(EXTSTD)) && !defined(BOOT)
|
||||
#if defined(BOLD_FONT) && (!defined(CPUM64) || defined(TELEMETRY_NONE)) && !defined(BOOT)
|
||||
#define BOLD_SPECIFIC_FONT
|
||||
extern const pm_uchar font_5x7_B[];
|
||||
#endif
|
||||
|
|
|
@ -98,7 +98,7 @@ PLAY_FUNCTION(playValue, source_t idx)
|
|||
case MIXSRC_FIRST_TELEM+TELEM_TIMER2-1:
|
||||
PLAY_DURATION(val, 0);
|
||||
break;
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
case MIXSRC_FIRST_TELEM+TELEM_RSSI_TX-1:
|
||||
case MIXSRC_FIRST_TELEM+TELEM_RSSI_RX-1:
|
||||
PLAY_NUMBER(val, 1+UNIT_DB, 0);
|
||||
|
@ -341,7 +341,7 @@ void evalFunctions()
|
|||
case FUNC_RESET_FLIGHT:
|
||||
flightReset();
|
||||
break;
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
case FUNC_RESET_TELEMETRY:
|
||||
telemetryReset();
|
||||
break;
|
||||
|
@ -537,7 +537,7 @@ void evalFunctions()
|
|||
}
|
||||
#endif
|
||||
|
||||
#if defined(FRSKY) && defined(VARIO)
|
||||
#if defined(TELEMETRY_FRSKY) && defined(VARIO)
|
||||
case FUNC_VARIO:
|
||||
newActiveFunctions |= (1 << FUNCTION_VARIO);
|
||||
break;
|
||||
|
|
|
@ -63,7 +63,7 @@ inline void drawSleepBitmap()
|
|||
#define LOAD_MODEL_BITMAP()
|
||||
|
||||
#define IS_MAIN_VIEW_DISPLAYED() menuHandlers[0] == menuMainView
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
#define IS_TELEMETRY_VIEW_DISPLAYED() menuHandlers[0] == menuTelemetryFrsky
|
||||
#else
|
||||
#define IS_TELEMETRY_VIEW_DISPLAYED() false
|
||||
|
|
|
@ -390,7 +390,7 @@ void lcdDrawNumber(coord_t x, coord_t y, lcdint_t val, LcdFlags flags, uint8_t l
|
|||
if (mode > 0)
|
||||
x += 2;
|
||||
}
|
||||
#if defined(BOLD_FONT) && !defined(CPUM64) || defined(EXTSTD)
|
||||
#if defined(BOLD_FONT) && !defined(CPUM64) || defined(TELEMETRY_NONE)
|
||||
if (flags & BOLD) fw += 1;
|
||||
#endif
|
||||
}
|
||||
|
@ -462,7 +462,7 @@ void lcdDrawNumber(coord_t x, coord_t y, lcdint_t val, LcdFlags flags, uint8_t l
|
|||
if (dblsize && (lcduint_t)val >= 1000 && (lcduint_t)val < 10000) x-=2;
|
||||
val = qr.quot;
|
||||
x -= fw;
|
||||
#if defined(BOLD_FONT) && !defined(CPUM64) || defined(EXTSTD)
|
||||
#if defined(BOLD_FONT) && !defined(CPUM64) || defined(TELEMETRY_NONE)
|
||||
if (i==len && (flags & BOLD)) x += 1;
|
||||
#endif
|
||||
}
|
||||
|
@ -915,7 +915,7 @@ void putsChannel(coord_t x, coord_t y, source_t channel, LcdFlags att)
|
|||
putsChannelValue(x, y, channel, value, att);
|
||||
}
|
||||
|
||||
#elif defined(FRSKY)
|
||||
#elif defined(TELEMETRY_FRSKY)
|
||||
void putsValueWithUnit(coord_t x, coord_t y, lcdint_t val, uint8_t unit, LcdFlags att)
|
||||
{
|
||||
convertUnit(val, unit);
|
||||
|
@ -954,7 +954,7 @@ void putsTelemetryChannelValue(coord_t x, coord_t y, uint8_t channel, lcdint_t v
|
|||
att &= ~NO_UNIT;
|
||||
putsTimer(x, y, val, att, att);
|
||||
break;
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
case TELEM_MIN_A1-1:
|
||||
case TELEM_MIN_A2-1:
|
||||
#if defined(CPUARM)
|
||||
|
@ -1044,7 +1044,7 @@ void putsTelemetryChannelValue(coord_t x, coord_t y, uint8_t channel, lcdint_t v
|
|||
putsValueWithUnit(x, y, val, UNIT_HDG, att);
|
||||
break;
|
||||
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
case TELEM_ALT-1:
|
||||
putsValueWithUnit(x, y, div_and_round(val, 10), UNIT_DIST, att|PREC1);
|
||||
break;
|
||||
|
@ -1073,7 +1073,7 @@ void putsTelemetryChannelValue(coord_t x, coord_t y, uint8_t channel, lcdint_t v
|
|||
}
|
||||
}
|
||||
}
|
||||
#else // defined(FRSKY)
|
||||
#else // defined(TELEMETRY_FRSKY)
|
||||
void putsTelemetryChannelValue(coord_t x, coord_t y, uint8_t channel, lcdint_t val, uint8_t att)
|
||||
{
|
||||
switch (channel) {
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
#include "opentx.h"
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
#include "view_mavlink.h"
|
||||
#endif
|
||||
|
||||
|
|
|
@ -385,7 +385,7 @@ void gvarWeightItem(coord_t x, coord_t y, MixData *md, uint8_t attr, uint8_t eve
|
|||
MD_UNION_TO_WEIGHT(weight, md);
|
||||
}
|
||||
|
||||
#if !defined(CPUM64) || !defined(FRSKY)
|
||||
#if !defined(CPUM64) || !defined(TELEMETRY_FRSKY)
|
||||
#define GAUGE_WIDTH 33
|
||||
#define GAUGE_HEIGHT 6
|
||||
void drawOffsetBar(uint8_t x, uint8_t y, MixData * md)
|
||||
|
@ -506,7 +506,7 @@ void menuModelMixOne(uint8_t event)
|
|||
MD_OFFSET_TO_UNION(md2, offset);
|
||||
offset.word = GVAR_MENU_ITEM(COLUMN_X+MIXES_2ND_COLUMN, y, offset.word, GV_RANGELARGE_OFFSET_NEG, GV_RANGELARGE_OFFSET, attr|LEFT, 0, event);
|
||||
MD_UNION_TO_OFFSET(offset, md2);
|
||||
#if !defined(CPUM64) || !defined(FRSKY)
|
||||
#if !defined(CPUM64) || !defined(TELEMETRY_FRSKY)
|
||||
drawOffsetBar(COLUMN_X+MIXES_2ND_COLUMN+22, y, md2);
|
||||
#endif
|
||||
break;
|
||||
|
|
|
@ -151,7 +151,7 @@ void menuModelLogicalSwitchOne(uint8_t event)
|
|||
INCDEC_ENABLE_CHECK(isSourceAvailable);
|
||||
}
|
||||
else {
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
if (v1_val >= MIXSRC_FIRST_TELEM) {
|
||||
#if defined(CPUARM)
|
||||
putsChannelValue(CSWONE_2ND_COLUMN, y, v1_val, convertLswTelemValue(cs), attr|LEFT);
|
||||
|
@ -380,7 +380,7 @@ void menuModelLogicalSwitches(uint8_t event)
|
|||
putsChannelValue(CSW_3RD_COLUMN, y, v1_val, calc100toRESX(cs->v2), LEFT|attr2);
|
||||
v2_min = -30000;
|
||||
v2_max = 30000;
|
||||
#elif defined(FRSKY)
|
||||
#elif defined(TELEMETRY_FRSKY)
|
||||
if (v1_val >= MIXSRC_FIRST_TELEM) {
|
||||
putsTelemetryChannelValue(CSW_3RD_COLUMN, y, v1_val - MIXSRC_FIRST_TELEM, convertLswTelemValue(cs), LEFT|attr2);
|
||||
v2_max = maxTelemValue(v1_val - MIXSRC_FIRST_TELEM + 1);
|
||||
|
|
|
@ -121,7 +121,7 @@ enum menuModelTelemetryItems {
|
|||
ITEM_TELEMETRY_MAX
|
||||
};
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
#define TELEM_COL1 INDENT_WIDTH
|
||||
#if defined(TRANSLATIONS_FR) || defined(TRANSLATIONS_CZ)
|
||||
#define TELEM_COL2 (9*FW)
|
||||
|
|
|
@ -233,7 +233,7 @@ void menuGeneralSetup(uint8_t event)
|
|||
#if defined(AUDIO)
|
||||
case ITEM_SETUP_BEEP_MODE:
|
||||
g_eeGeneral.beepMode = selectMenuItem(RADIO_SETUP_2ND_COLUMN, y, STR_SPEAKER, STR_VBEEPMODE, g_eeGeneral.beepMode, -2, 1, attr, event);
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
if (attr && checkIncDec_Ret) frskySendAlarms();
|
||||
#endif
|
||||
break;
|
||||
|
@ -241,7 +241,7 @@ void menuGeneralSetup(uint8_t event)
|
|||
#if defined(BUZZER)
|
||||
case ITEM_SETUP_BUZZER_MODE:
|
||||
g_eeGeneral.buzzerMode = selectMenuItem(RADIO_SETUP_2ND_COLUMN, y, STR_BUZZER, STR_VBEEPMODE, g_eeGeneral.buzzerMode, -2, 1, attr, event);
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
if (attr && checkIncDec_Ret) frskySendAlarms();
|
||||
#endif
|
||||
break;
|
||||
|
@ -249,7 +249,7 @@ void menuGeneralSetup(uint8_t event)
|
|||
#elif defined(BUZZER)
|
||||
case ITEM_SETUP_BUZZER_MODE:
|
||||
g_eeGeneral.beepMode = selectMenuItem(RADIO_SETUP_2ND_COLUMN, y, STR_SPEAKER, STR_VBEEPMODE, g_eeGeneral.beepMode, -2, 1, attr, event);
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
if (attr && checkIncDec_Ret) frskySendAlarms();
|
||||
#endif
|
||||
break;
|
||||
|
@ -470,7 +470,7 @@ void menuGeneralSetup(uint8_t event)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if defined(FRSKY) && defined(FRSKY_HUB) && defined(GPS)
|
||||
#if defined(TELEMETRY_FRSKY) && defined(FRSKY_HUB) && defined(GPS)
|
||||
case ITEM_SETUP_TIMEZONE:
|
||||
lcd_putsLeft(y, STR_TIMEZONE);
|
||||
lcdDrawNumber(RADIO_SETUP_2ND_COLUMN, y, g_eeGeneral.timezone, attr|LEFT);
|
||||
|
@ -518,7 +518,7 @@ void menuGeneralSetup(uint8_t event)
|
|||
break;
|
||||
#endif
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
case ITEM_MAVLINK_BAUD:
|
||||
g_eeGeneral.mavbaud = selectMenuItem(RADIO_SETUP_2ND_COLUMN, y, STR_MAVLINK_BAUD_LABEL, STR_MAVLINK_BAUDS, g_eeGeneral.mavbaud, 0, 7, attr, event);
|
||||
break;
|
||||
|
|
|
@ -81,7 +81,7 @@ void displayTrims(uint8_t phase)
|
|||
uint8_t att = ROUND;
|
||||
int16_t val = getTrimValue(phase, i);
|
||||
|
||||
#if !defined(CPUM64) || !defined(FRSKY)
|
||||
#if !defined(CPUM64) || !defined(TELEMETRY_FRSKY)
|
||||
int16_t dir = val;
|
||||
bool exttrim = false;
|
||||
if (val < TRIM_MIN || val > TRIM_MAX) {
|
||||
|
@ -106,7 +106,7 @@ void displayTrims(uint8_t phase)
|
|||
lcdDrawSolidVerticalLine(xm+1, ym-1, 3);
|
||||
}
|
||||
ym -= val;
|
||||
#if !defined(CPUM64) || !defined(FRSKY)
|
||||
#if !defined(CPUM64) || !defined(TELEMETRY_FRSKY)
|
||||
lcdDrawFilledRect(xm-3, ym-3, 7, 7, SOLID, att|ERASE);
|
||||
if (dir >= 0) {
|
||||
lcdDrawSolidHorizontalLine(xm-1, ym-1, 3);
|
||||
|
@ -132,7 +132,7 @@ void displayTrims(uint8_t phase)
|
|||
lcdDrawSolidHorizontalLine(xm-1, ym-1, 3);
|
||||
lcdDrawSolidHorizontalLine(xm-1, ym+1, 3);
|
||||
xm += val;
|
||||
#if !defined(CPUM64) || !defined(FRSKY)
|
||||
#if !defined(CPUM64) || !defined(TELEMETRY_FRSKY)
|
||||
lcdDrawFilledRect(xm-3, ym-3, 7, 7, SOLID, att|ERASE);
|
||||
if (dir >= 0) {
|
||||
lcdDrawSolidVerticalLine(xm+1, ym-1, 3);
|
||||
|
@ -249,12 +249,12 @@ void onMainViewMenu(const char *result)
|
|||
POPUP_MENU_ADD_ITEM(STR_RESET_TIMER1);
|
||||
POPUP_MENU_ADD_ITEM(STR_RESET_TIMER2);
|
||||
POPUP_MENU_ADD_ITEM(STR_RESET_TIMER3);
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
POPUP_MENU_ADD_ITEM(STR_RESET_TELEMETRY);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
else if (result == STR_RESET_TELEMETRY) {
|
||||
telemetryReset();
|
||||
}
|
||||
|
@ -328,7 +328,7 @@ void menuMainView(uint8_t event)
|
|||
#else
|
||||
POPUP_MENU_ADD_ITEM(STR_RESET_TIMER1);
|
||||
POPUP_MENU_ADD_ITEM(STR_RESET_TIMER2);
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
POPUP_MENU_ADD_ITEM(STR_RESET_TELEMETRY);
|
||||
#endif
|
||||
POPUP_MENU_ADD_ITEM(STR_RESET_FLIGHT);
|
||||
|
@ -373,19 +373,19 @@ void menuMainView(uint8_t event)
|
|||
break;
|
||||
|
||||
case EVT_KEY_TELEMETRY:
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
if (!IS_FAI_ENABLED())
|
||||
chainMenu(menuTelemetryFrsky);
|
||||
#elif defined(JETI)
|
||||
#elif defined(TELEMETRY_JETI)
|
||||
JETI_EnableRXD(); // enable JETI-Telemetry reception
|
||||
chainMenu(menuTelemetryJeti);
|
||||
#elif defined(ARDUPILOT)
|
||||
#elif defined(TELEMETRY_ARDUPILOT)
|
||||
ARDUPILOT_EnableRXD(); // enable ArduPilot-Telemetry reception
|
||||
chainMenu(menuTelemetryArduPilot);
|
||||
#elif defined(NMEA)
|
||||
#elif defined(TELEMETRY_NMEA)
|
||||
NMEA_EnableRXD(); // enable NMEA-Telemetry reception
|
||||
chainMenu(menuTelemetryNMEA);
|
||||
#elif defined(MAVLINK)
|
||||
#elif defined(TELEMETRY_MAVLINK)
|
||||
chainMenu(menuTelemetryMavlink);
|
||||
#else
|
||||
chainMenu(menuStatisticsDebug);
|
||||
|
|
|
@ -55,7 +55,7 @@ void displayRssiLine()
|
|||
}
|
||||
}
|
||||
|
||||
#if defined(FRSKY) && defined(FRSKY_HUB) && defined(GPS) && !defined(CPUARM)
|
||||
#if defined(TELEMETRY_FRSKY) && defined(FRSKY_HUB) && defined(GPS) && !defined(CPUARM)
|
||||
void displayGpsTime()
|
||||
{
|
||||
uint8_t att = (TELEMETRY_STREAMING() ? LEFT|LEADING0 : LEFT|LEADING0|BLINK);
|
||||
|
|
|
@ -71,7 +71,7 @@ void onMainViewMenu(const char *result);
|
|||
void menuMainViewChannelsMonitor(uint8_t event);
|
||||
void menuChannelsView(uint8_t event);
|
||||
void menuMainView(uint8_t event);
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
void menuTelemetryFrsky(uint8_t event);
|
||||
#endif
|
||||
void menuCustomFunctions(uint8_t event, CustomFunctionData * functions, CustomFunctionsContext * functionsContext);
|
||||
|
|
|
@ -215,7 +215,7 @@ void menuGeneralSetup(uint8_t event)
|
|||
|
||||
case ITEM_SETUP_BEEP_MODE:
|
||||
g_eeGeneral.beepMode = selectMenuItem(RADIO_SETUP_2ND_COLUMN, y, STR_SPEAKER, STR_VBEEPMODE, g_eeGeneral.beepMode, -2, 1, attr, event);
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
if (attr && checkIncDec_Ret) frskySendAlarms();
|
||||
#endif
|
||||
break;
|
||||
|
@ -402,7 +402,7 @@ void menuGeneralSetup(uint8_t event)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if defined(FRSKY) && defined(FRSKY_HUB) && defined(GPS)
|
||||
#if defined(TELEMETRY_FRSKY) && defined(FRSKY_HUB) && defined(GPS)
|
||||
case ITEM_SETUP_LABEL_GPS:
|
||||
lcd_putsLeft(y, STR_GPS);
|
||||
break;
|
||||
|
@ -456,7 +456,7 @@ void menuGeneralSetup(uint8_t event)
|
|||
break;
|
||||
#endif
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
case ITEM_MAVLINK_BAUD:
|
||||
g_eeGeneral.mavbaud = selectMenuItem(RADIO_SETUP_2ND_COLUMN, y, STR_MAVLINK_BAUD_LABEL, STR_MAVLINK_BAUDS, g_eeGeneral.mavbaud, 0, 7, attr, event);
|
||||
break;
|
||||
|
|
|
@ -226,7 +226,7 @@ bool menuGeneralSetup(evt_t event)
|
|||
case ITEM_SETUP_BEEP_MODE:
|
||||
lcdDrawText(MENUS_MARGIN_LEFT, y, STR_SPEAKER);
|
||||
g_eeGeneral.beepMode = selectMenuItem(RADIO_SETUP_2ND_COLUMN, y, STR_VBEEPMODE, g_eeGeneral.beepMode, -2, 1, attr, event);
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
if (attr && checkIncDec_Ret) frskySendAlarms();
|
||||
#endif
|
||||
break;
|
||||
|
@ -470,7 +470,7 @@ bool menuGeneralSetup(evt_t event)
|
|||
break;
|
||||
#endif
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
case ITEM_MAVLINK_BAUD:
|
||||
lcdDrawText(MENUS_MARGIN_LEFT, y, STR_MAVLINK_BAUD_LABEL);
|
||||
g_eeGeneral.mavbaud = selectMenuItem(RADIO_SETUP_2ND_COLUMN, y, STR_MAVLINK_BAUDS, g_eeGeneral.mavbaud, 0, 7, attr, event);
|
||||
|
|
|
@ -218,7 +218,7 @@ bool isSourceAvailableInCustomSwitches(int source)
|
|||
{
|
||||
bool result = isSourceAvailable(source);
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
if (result && source>=MIXSRC_FIRST_TELEM && source<=MIXSRC_LAST_TELEM) {
|
||||
div_t qr = div(source-MIXSRC_FIRST_TELEM, 3);
|
||||
result = isTelemetryFieldComparisonAvailable(qr.quot);
|
||||
|
|
|
@ -136,7 +136,7 @@ void writeHeader()
|
|||
f_puts("Time,", &g_oLogFile);
|
||||
#endif
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
#if !defined(CPUARM)
|
||||
f_puts("Buffer,RX,TX,A1,A2,", &g_oLogFile);
|
||||
#if defined(FRSKY_HUB)
|
||||
|
@ -234,7 +234,7 @@ void writeLogs()
|
|||
f_printf(&g_oLogFile, "%d,", tmr10ms);
|
||||
#endif
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
#if !defined(CPUARM)
|
||||
f_printf(&g_oLogFile, "%d,%d,%d,", telemetryStreaming, RAW_FRSKY_MINMAX(telemetryData.rssi[0]), RAW_FRSKY_MINMAX(telemetryData.rssi[1]));
|
||||
for (uint8_t i=0; i<MAX_FRSKY_A_CHANNELS; i++) {
|
||||
|
|
|
@ -103,7 +103,7 @@ void perMain()
|
|||
if (evt && (g_eeGeneral.backlightMode & e_backlight_mode_keys)) backlightOn(); // on keypress turn the light on
|
||||
doLoopCommonActions();
|
||||
|
||||
#if defined(FRSKY) || defined(MAVLINK)
|
||||
#if defined(TELEMETRY_FRSKY) || defined(TELEMETRY_MAVLINK)
|
||||
telemetryWakeup();
|
||||
#endif
|
||||
|
||||
|
|
|
@ -368,12 +368,12 @@ getvalue_t getValue(mixsrc_t i)
|
|||
return telemetryItem.value;
|
||||
}
|
||||
}
|
||||
#elif defined(FRSKY)
|
||||
#elif defined(TELEMETRY_FRSKY)
|
||||
else if (i==MIXSRC_FIRST_TELEM-1+TELEM_RSSI_TX) return telemetryData.rssi[1].value;
|
||||
else if (i==MIXSRC_FIRST_TELEM-1+TELEM_RSSI_RX) return telemetryData.rssi[0].value;
|
||||
else if (i==MIXSRC_FIRST_TELEM-1+TELEM_A1) return telemetryData.analog[TELEM_ANA_A1].value;
|
||||
else if (i==MIXSRC_FIRST_TELEM-1+TELEM_A2) return telemetryData.analog[TELEM_ANA_A2].value;
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
else if (i==MIXSRC_FIRST_TELEM-1+TELEM_ALT) return telemetryData.hub.baroAltitude;
|
||||
#elif defined(FRSKY_HUB) || defined(WS_HOW_HIGH)
|
||||
else if (i==MIXSRC_FIRST_TELEM-1+TELEM_ALT) return TELEMETRY_RELATIVE_BARO_ALT_BP;
|
||||
|
|
|
@ -380,14 +380,14 @@ enum TelemetrySensorFormula
|
|||
#endif
|
||||
|
||||
enum VarioSource {
|
||||
#if !defined(FRSKY_SPORT)
|
||||
#if !defined(TELEMETRY_FRSKY_SPORT)
|
||||
VARIO_SOURCE_ALTI,
|
||||
VARIO_SOURCE_ALTI_PLUS,
|
||||
#endif
|
||||
VARIO_SOURCE_VSPEED,
|
||||
VARIO_SOURCE_A1,
|
||||
VARIO_SOURCE_A2,
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
VARIO_SOURCE_DTE,
|
||||
#endif
|
||||
VARIO_SOURCE_COUNT,
|
||||
|
|
|
@ -153,7 +153,7 @@ void per10ms()
|
|||
}
|
||||
#endif
|
||||
|
||||
#if defined(FRSKY) || defined(JETI)
|
||||
#if defined(TELEMETRY_FRSKY) || defined(TELEMETRY_JETI)
|
||||
if (!IS_DSM2_SERIAL_PROTOCOL(s_current_protocol[0])) {
|
||||
telemetryInterrupt10ms();
|
||||
}
|
||||
|
@ -440,7 +440,7 @@ void modelDefault(uint8_t id)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
g_model.mavlink.rc_rssi_scale = 15;
|
||||
g_model.mavlink.pc_rssi_en = 1;
|
||||
#endif
|
||||
|
@ -787,7 +787,7 @@ getvalue_t convert8bitsTelemValue(source_t channel, ls_telemetry_value_t value)
|
|||
return value;
|
||||
}
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
ls_telemetry_value_t minTelemValue(source_t channel)
|
||||
{
|
||||
return 0;
|
||||
|
@ -804,7 +804,7 @@ ls_telemetry_value_t max8bitsTelemValue(source_t channel)
|
|||
return 30000;
|
||||
}
|
||||
|
||||
#elif defined(FRSKY)
|
||||
#elif defined(TELEMETRY_FRSKY)
|
||||
|
||||
/*
|
||||
ls_telemetry_value_t minTelemValue(uint8_t channel)
|
||||
|
@ -858,7 +858,7 @@ getvalue_t convert8bitsTelemValue(uint8_t channel, ls_telemetry_value_t value)
|
|||
case TELEM_TIMER2:
|
||||
result = value * 5;
|
||||
break;
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
case TELEM_ALT:
|
||||
case TELEM_GPSALT:
|
||||
case TELEM_MAX_ALT:
|
||||
|
@ -1624,7 +1624,7 @@ void flightReset(uint8_t check)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
telemetryReset();
|
||||
#endif
|
||||
|
||||
|
@ -1949,7 +1949,7 @@ void opentxClose(uint8_t shutdown)
|
|||
#endif
|
||||
pausePulses(); // stop mixer task to disable trims processing while in shutdown
|
||||
AUDIO_BYE();
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
// TODO needed? telemetryEnd();
|
||||
#endif
|
||||
#if defined(LUA)
|
||||
|
@ -2273,7 +2273,7 @@ FORCEINLINE void DSM2_USART_vect()
|
|||
|
||||
#if !defined(SIMU) && !defined(CPUARM)
|
||||
|
||||
#if defined (FRSKY)
|
||||
#if defined (TELEMETRY_FRSKY)
|
||||
|
||||
FORCEINLINE void FRSKY_USART_vect()
|
||||
{
|
||||
|
@ -2288,14 +2288,14 @@ FORCEINLINE void FRSKY_USART_vect()
|
|||
// USART0/1 Transmit Data Register Emtpy ISR
|
||||
ISR(USART_UDRE_vect_N(TLM_USART))
|
||||
{
|
||||
#if defined(FRSKY) && defined(DSM2_SERIAL)
|
||||
#if defined(TELEMETRY_FRSKY) && defined(DSM2_SERIAL)
|
||||
if (IS_DSM2_PROTOCOL(g_model.protocol)) { // TODO not s_current_protocol?
|
||||
DSM2_USART_vect();
|
||||
}
|
||||
else {
|
||||
FRSKY_USART_vect();
|
||||
}
|
||||
#elif defined(FRSKY)
|
||||
#elif defined(TELEMETRY_FRSKY)
|
||||
FRSKY_USART_vect();
|
||||
#else
|
||||
DSM2_USART_vect();
|
||||
|
@ -2646,11 +2646,11 @@ int main()
|
|||
|
||||
sei(); // interrupts needed now
|
||||
|
||||
#if !defined(CPUARM) && defined(FRSKY) && !defined(DSM2_SERIAL)
|
||||
#if !defined(CPUARM) && defined(TELEMETRY_FRSKY) && !defined(DSM2_SERIAL)
|
||||
telemetryInit();
|
||||
#endif
|
||||
|
||||
#if defined(DSM2_SERIAL) && !defined(FRSKY)
|
||||
#if defined(DSM2_SERIAL) && !defined(TELEMETRY_FRSKY)
|
||||
DSM2_Init();
|
||||
#endif
|
||||
|
||||
|
|
|
@ -97,7 +97,7 @@
|
|||
#define CASE_PWM_BACKLIGHT(x)
|
||||
#endif
|
||||
|
||||
#if defined(FRSKY) && defined(FRSKY_HUB) && defined(GPS)
|
||||
#if defined(TELEMETRY_FRSKY) && defined(FRSKY_HUB) && defined(GPS)
|
||||
#define CASE_GPS(x) x,
|
||||
#else
|
||||
#define CASE_GPS(x)
|
||||
|
@ -121,13 +121,13 @@
|
|||
#define CASE_SPLASH(x)
|
||||
#endif
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
#define CASE_FRSKY(x) x,
|
||||
#else
|
||||
#define CASE_FRSKY(x)
|
||||
#endif
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
#define CASE_MAVLINK(x) x,
|
||||
#else
|
||||
#define CASE_MAVLINK(x)
|
||||
|
@ -1555,7 +1555,7 @@ extern bar_threshold_t barsThresholds[THLD_MAX];
|
|||
#define FILL_THRESHOLD(idx, val)
|
||||
#endif
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
ls_telemetry_value_t minTelemValue(source_t channel);
|
||||
ls_telemetry_value_t maxTelemValue(source_t channel);
|
||||
#else
|
||||
|
@ -1581,7 +1581,7 @@ getvalue_t convertLswTelemValue(LogicalSwitchData * cs);
|
|||
#define maxBarTelemValue(channel) maxTelemValue(channel)
|
||||
#endif
|
||||
|
||||
#if defined(FRSKY) || defined(CPUARM)
|
||||
#if defined(TELEMETRY_FRSKY) || defined(CPUARM)
|
||||
lcdint_t applyChannelRatio(source_t channel, lcdint_t val);
|
||||
#define ANA_CHANNEL_UNIT(channel) g_model.frsky.channels[channel].type
|
||||
#endif
|
||||
|
@ -1600,7 +1600,7 @@ inline int div_and_round(int num, int den)
|
|||
return num / den;
|
||||
}
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
NOINLINE uint8_t getRssiAlarmValue(uint8_t alarm);
|
||||
|
||||
extern const pm_uint8_t bchunit_ar[];
|
||||
|
@ -1652,7 +1652,7 @@ void varioWakeup();
|
|||
|
||||
#if defined(CPUARM)
|
||||
void putsValueWithUnit(coord_t x, coord_t y, int32_t val, uint8_t unit, LcdFlags att);
|
||||
#elif defined(FRSKY)
|
||||
#elif defined(TELEMETRY_FRSKY)
|
||||
FORCEINLINE void convertUnit(getvalue_t & val, uint8_t & unit)
|
||||
{
|
||||
if (IS_IMPERIAL_ENABLE()) {
|
||||
|
@ -1695,7 +1695,7 @@ FORCEINLINE void convertUnit(getvalue_t & val, uint8_t & unit)
|
|||
#define IS_USR_PROTO_WS_HOW_HIGH() (g_model.frsky.usrProto == USR_PROTO_WS_HOW_HIGH)
|
||||
#endif
|
||||
|
||||
#if defined(FRSKY) && defined(FRSKY_HUB) && defined(GPS)
|
||||
#if defined(TELEMETRY_FRSKY) && defined(FRSKY_HUB) && defined(GPS)
|
||||
#define IS_GPS_AVAILABLE() IS_USR_PROTO_FRSKY_HUB()
|
||||
#else
|
||||
#define IS_GPS_AVAILABLE() (0)
|
||||
|
|
|
@ -762,7 +762,7 @@ void setupPulses()
|
|||
|
||||
if (s_current_protocol[0] != required_protocol) {
|
||||
|
||||
#if defined(DSM2_SERIAL) && defined(FRSKY)
|
||||
#if defined(DSM2_SERIAL) && defined(TELEMETRY_FRSKY)
|
||||
if (s_current_protocol[0] == 255 || IS_DSM2_PROTOCOL(s_current_protocol[0])) {
|
||||
telemetryInit();
|
||||
}
|
||||
|
@ -852,7 +852,7 @@ void setupPulses()
|
|||
PORTB &= ~(1<<OUT_B_PPM); // Hold PPM output low
|
||||
break;
|
||||
|
||||
#if defined(DSM2_SERIAL) && defined(FRSKY)
|
||||
#if defined(DSM2_SERIAL) && defined(TELEMETRY_FRSKY)
|
||||
case PROTO_DSM2_LP45:
|
||||
case PROTO_DSM2_DSM2:
|
||||
case PROTO_DSM2_DSMX:
|
||||
|
|
|
@ -541,7 +541,7 @@ int main(int argc,char **argv)
|
|||
th9xSim->show(); // Otherwise the main window gets centred across my two monitors, split down the middle.
|
||||
#endif
|
||||
|
||||
#if defined(FRSKY) && !defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY) && !defined(TELEMETRY_FRSKY_SPORT)
|
||||
telemetryStreaming = 1;
|
||||
#endif
|
||||
|
||||
|
|
|
@ -89,7 +89,7 @@ void postModelLoad(bool alarms)
|
|||
resumeMixerCalculations();
|
||||
// TODO pulses should be started after mixer calculations ...
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
frskySendAlarms();
|
||||
#endif
|
||||
|
||||
|
|
|
@ -385,7 +385,7 @@ bool getLogicalSwitch(uint8_t idx)
|
|||
}
|
||||
else {
|
||||
mixsrc_t v1 = ls->v1;
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
// Telemetry
|
||||
if (v1 >= MIXSRC_FIRST_TELEM) {
|
||||
#if defined(CPUARM)
|
||||
|
@ -485,7 +485,7 @@ bool getLogicalSwitch(uint8_t idx)
|
|||
}
|
||||
}
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
DurationAndDelayProcessing:
|
||||
#endif
|
||||
|
||||
|
|
|
@ -191,7 +191,7 @@ void processMultiplexAna()
|
|||
#if !defined(SIMU) && (defined(TELEMETRY_MOD_14051) || defined(TELEMETRY_MOD_14051_SWAPPED))
|
||||
#define THR_STATE() pf7_digital[PF7_THR]
|
||||
#define AIL_STATE() pf7_digital[PF7_AIL]
|
||||
#elif defined(JETI) || defined(FRSKY) || defined(ARDUPILOT) || defined(NMEA) || defined(MAVLINK)
|
||||
#elif defined(TELEMETRY_JETI) || defined(TELEMETRY_FRSKY) || defined(TELEMETRY_ARDUPILOT) || defined(TELEMETRY_NMEA) || defined(TELEMETRY_MAVLINK)
|
||||
#define THR_STATE() (PINC & (1<<INP_C_ThrCt))
|
||||
#define AIL_STATE() (PINC & (1<<INP_C_AileDR))
|
||||
#else
|
||||
|
|
|
@ -163,7 +163,7 @@ bool checkSlaveMode();
|
|||
#define OUT_E_BUZZER 3
|
||||
#define INP_E_ElevDR 2
|
||||
|
||||
#if defined(JETI) || defined(FRSKY) || defined(ARDUPILOT) || defined(NMEA) || defined(MAVLINK)
|
||||
#if defined(TELEMETRY_JETI) || defined(TELEMETRY_FRSKY) || defined(TELEMETRY_ARDUPILOT) || defined(TELEMETRY_NMEA) || defined(TELEMETRY_MAVLINK)
|
||||
#define INP_C_ThrCt 6
|
||||
#define INP_C_AileDR 7
|
||||
#else
|
||||
|
|
|
@ -73,7 +73,7 @@ if(MULTIMODULE)
|
|||
set(SRC ${SRC} pulses/multi_arm.cpp telemetry/spektrum.cpp)
|
||||
endif()
|
||||
add_definitions(-DCPUARM)
|
||||
add_definitions(-DFRSKY -DFRSKY_SPORT -DFRSKY_HUB -DGPS -DPXX -DDSM2)
|
||||
add_definitions(-DTELEMETRY_FRSKY -DTELEMETRY_FRSKY_SPORT -DFRSKY_HUB -DGPS -DPXX -DDSM2)
|
||||
add_definitions(-DBOLD_FONT -DBATTGRAPH -DTHRTRACE)
|
||||
include_directories(${COOS_DIR} ${COOS_DIR}/kernel ${COOS_DIR}/portable)
|
||||
foreach(LANGUAGE ${TTS_LANGUAGES})
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
option(EXT "Telemetry protocol" OFF) # TODO rename this EXT option to TELEMETRY
|
||||
option(TELEMETRY "Telemetry protocol" OFF)
|
||||
option(AUDIO "Audio support" OFF)
|
||||
option(VOICE "Voice support" OFF)
|
||||
option(GRAPHICS "Additional graphics" ON)
|
||||
|
@ -54,37 +54,37 @@ if(HAPTIC)
|
|||
add_definitions(-DHAPTIC)
|
||||
set(SRC ${SRC} haptic.cpp)
|
||||
endif()
|
||||
if(${EXT} STREQUAL OFF)
|
||||
add_definitions(-DEXTSTD)
|
||||
elseif(EXT STREQUAL ARDUPILOT)
|
||||
add_definitions(-DARDUPILOT)
|
||||
if(${TELEMETRY} STREQUAL OFF)
|
||||
add_definitions(-DTELEMETRY_NONE)
|
||||
elseif(TELEMETRY STREQUAL ARDUPILOT)
|
||||
add_definitions(-DTELEMETRY_ARDUPILOT)
|
||||
set(SRC ${SRC} telemetry/ardupilot.cpp)
|
||||
elseif(EXT STREQUAL NMEA)
|
||||
add_definitions(-DNMEA)
|
||||
elseif(TELEMETRY STREQUAL NMEA)
|
||||
add_definitions(-DTELEMETRY_NMEA)
|
||||
set(SRC ${SRC} telemetry/nmea.cpp)
|
||||
elseif(EXT STREQUAL JETI)
|
||||
add_definitions(-DJETI)
|
||||
elseif(TELEMETRY STREQUAL JETI)
|
||||
add_definitions(-DTELEMETRY_JETI)
|
||||
set(SRC ${SRC} telemetry/jeti.cpp)
|
||||
elseif(EXT STREQUAL MAVLINK)
|
||||
add_definitions(-DMAVLINK)
|
||||
elseif(TELEMETRY STREQUAL MAVLINK)
|
||||
add_definitions(-DTELEMETRY_MAVLINK)
|
||||
include_directories(${THIRDPARTY_DIR} gui/${GUI_DIR} targets/common/avr)
|
||||
set(SRC ${SRC} telemetry/mavlink.cpp targets/common/avr/serial_driver.cpp)
|
||||
set(GUI_SRC ${GUI_SRC} view_mavlink.cpp)
|
||||
math(EXPR EEPROM_VARIANT ${EEPROM_VARIANT}+${MAVLINK_VARIANT})
|
||||
elseif(EXT STREQUAL TELEMETREZ)
|
||||
add_definitions(-DTELEMETREZ)
|
||||
elseif(TELEMETRY STREQUAL TELEMETREZ)
|
||||
add_definitions(-DTELEMETRY_TELEMETREZ)
|
||||
set(SRC ${SRC} telemetry/jeti.cpp)
|
||||
elseif(EXT STREQUAL FRSKY_SPORT)
|
||||
add_definitions(-DFRSKY_SPORT)
|
||||
elseif(TELEMETRY STREQUAL FRSKY_SPORT)
|
||||
add_definitions(-DTELEMETRY_FRSKY_SPORT)
|
||||
set(SRC ${SRC} crc16.cpp telemetry/frsky_sport.cpp)
|
||||
endif()
|
||||
if(EXT STREQUAL FRSKY OR EXT STREQUAL FRSKY_SPORT OR EXT STREQUAL TELEMETREZ)
|
||||
if(TELEMETRY STREQUAL FRSKY OR TELEMETRY STREQUAL FRSKY_SPORT OR TELEMETRY STREQUAL TELEMETREZ)
|
||||
option(FRSKY_HUB "FrSky Hub support" ON)
|
||||
option(WS_HOW_HIGH "Winged Shadow sensors support" ON)
|
||||
option(GAUGES "Telemetry gauges" OFF)
|
||||
option(GPS "GPS support" ON)
|
||||
option(VARIO "Vario support" ON)
|
||||
add_definitions(-DFRSKY)
|
||||
add_definitions(-DTELEMETRY_FRSKY)
|
||||
set(SRC ${SRC} telemetry/telemetry.cpp telemetry/telemetry_holders.cpp telemetry/frsky.cpp telemetry/frsky_d.cpp)
|
||||
set(FIRMWARE_SRC ${FIRMWARE_SRC} targets/common/avr/telemetry_driver.cpp)
|
||||
set(GUI_SRC ${GUI_SRC} view_telemetry.cpp)
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
#include "opentx.h"
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
|
||||
void telemetryEnableTx(void)
|
||||
{
|
||||
|
|
|
@ -192,14 +192,14 @@ const char * OpenTxSimulator::getError()
|
|||
|
||||
void OpenTxSimulator::sendTelemetry(uint8_t * data, unsigned int len)
|
||||
{
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
processSportPacket(data);
|
||||
#endif
|
||||
}
|
||||
|
||||
uint8_t OpenTxSimulator::getSensorInstance(uint16_t id, uint8_t defaultValue)
|
||||
{
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
for (int i = 0; i<MAX_SENSORS; i++) {
|
||||
if (isTelemetryFieldAvailable(i)) {
|
||||
TelemetrySensor * sensor = &g_model.telemetrySensors[i];
|
||||
|
@ -214,7 +214,7 @@ uint8_t OpenTxSimulator::getSensorInstance(uint16_t id, uint8_t defaultValue)
|
|||
|
||||
uint16_t OpenTxSimulator::getSensorRatio(uint16_t id)
|
||||
{
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
for (int i = 0; i<MAX_SENSORS; i++) {
|
||||
if (isTelemetryFieldAvailable(i)) {
|
||||
TelemetrySensor * sensor = &g_model.telemetrySensors[i];
|
||||
|
|
|
@ -284,7 +284,7 @@ void simuSetSwitch(uint8_t swtch, int8_t state)
|
|||
SWITCH_CASE(5, ping, 1<<INP_G_Gear)
|
||||
SWITCH_CASE(6, pinb, 1<<INP_L_Trainer)
|
||||
#else // PCB9X
|
||||
#if defined(JETI) || defined(FRSKY) || defined(NMEA) || defined(ARDUPILOT) || defined(MAVLINK)
|
||||
#if defined(TELEMETRY_JETI) || defined(TELEMETRY_FRSKY) || defined(TELEMETRY_NMEA) || defined(TELEMETRY_ARDUPILOT) || defined(TELEMETRY_MAVLINK)
|
||||
SWITCH_CASE(0, pinc, 1<<INP_C_ThrCt)
|
||||
SWITCH_CASE(4, pinc, 1<<INP_C_AileDR)
|
||||
#else
|
||||
|
|
|
@ -105,7 +105,7 @@ extern "C" void UART0_IRQHandler()
|
|||
#define SECOND_UART_Configure(...)
|
||||
#endif
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
void serial2TelemetryInit(unsigned int /*protocol*/)
|
||||
{
|
||||
SECOND_UART_Configure(FRSKY_D_BAUDRATE, Master_frequency);
|
||||
|
|
|
@ -171,7 +171,7 @@ void mixerTask(void * pdata)
|
|||
CoLeaveMutexSection(mixerMutex);
|
||||
DEBUG_TIMER_STOP(debugTimerMixer);
|
||||
|
||||
#if defined(FRSKY) || defined(MAVLINK)
|
||||
#if defined(TELEMETRY_FRSKY) || defined(TELEMETRY_MAVLINK)
|
||||
DEBUG_TIMER_START(debugTimerTelemetryWakeup);
|
||||
telemetryWakeup();
|
||||
DEBUG_TIMER_STOP(debugTimerTelemetryWakeup);
|
||||
|
|
|
@ -163,7 +163,7 @@ NOINLINE void processFrskyTelemetryData(uint8_t data)
|
|||
#endif
|
||||
} // switch
|
||||
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
if (IS_FRSKY_SPORT_PROTOCOL() && telemetryRxBufferCount >= FRSKY_SPORT_PACKET_SIZE) {
|
||||
processSportPacket(telemetryRxBuffer);
|
||||
dataState = STATE_DATA_IDLE;
|
||||
|
|
|
@ -21,19 +21,19 @@
|
|||
#ifndef _TELEMETRY_H_
|
||||
#define _TELEMETRY_H_
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
// FrSky Telemetry
|
||||
#include "frsky.h"
|
||||
#elif defined(JETI)
|
||||
#elif defined(TELEMETRY_JETI)
|
||||
// Jeti-DUPLEX Telemetry
|
||||
#include "jeti.h"
|
||||
#elif defined(ARDUPILOT)
|
||||
#elif defined(TELEMETRY_ARDUPILOT)
|
||||
// ArduPilot Telemetry
|
||||
#include "ardupilot.h"
|
||||
#elif defined(NMEA)
|
||||
#elif defined(TELEMETRY_NMEA)
|
||||
// NMEA Telemetry
|
||||
#include "nmea.h"
|
||||
#elif defined(MAVLINK)
|
||||
#elif defined(TELEMETRY_MAVLINK)
|
||||
// Mavlink Telemetry
|
||||
#include "mavlink.h"
|
||||
#endif
|
||||
|
|
|
@ -483,12 +483,12 @@ void setTelemetryValue(TelemetryProtocol protocol, uint16_t id, uint8_t subId, u
|
|||
int index = availableTelemetryIndex();
|
||||
if (index >= 0) {
|
||||
switch (protocol) {
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
case TELEM_PROTO_FRSKY_SPORT:
|
||||
frskySportSetDefault(index, id, subId, instance);
|
||||
break;
|
||||
#endif
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
case TELEM_PROTO_FRSKY_D:
|
||||
frskyDSetDefault(index, id);
|
||||
break;
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
|
||||
void frskyDProcessPacket(uint8_t *packet);
|
||||
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
bool checkSportPacket(uint8_t *packet);
|
||||
void processSportPacket(uint8_t * packet);
|
||||
bool checkSportPacket(uint8_t *packet);
|
||||
|
@ -30,7 +30,7 @@ void frskyCalculateCellStats(void);
|
|||
void displayVoltagesScreen();
|
||||
#endif
|
||||
|
||||
#if defined(FRSKY) && !defined(CPUARM)
|
||||
#if defined(TELEMETRY_FRSKY) && !defined(CPUARM)
|
||||
TEST(FrSky, gpsNfuel)
|
||||
{
|
||||
g_model.frsky.usrProto = 1;
|
||||
|
@ -77,7 +77,7 @@ TEST(FrSky, dateNtime)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if defined(FRSKY) && defined(CPUARM)
|
||||
#if defined(TELEMETRY_FRSKY) && defined(CPUARM)
|
||||
TEST(FrSky, TelemetryValueWithMinAveraging)
|
||||
{
|
||||
/*
|
||||
|
@ -173,9 +173,9 @@ TEST(FrSky, HubAltNegative)
|
|||
processHubPacket(BARO_ALT_AP_ID, 05);
|
||||
EXPECT_EQ(telemetryItems[0].value, 120);
|
||||
}
|
||||
#endif // defined(FRSKY) && defined(CPUARM)
|
||||
#endif // defined(TELEMETRY_FRSKY) && defined(CPUARM)
|
||||
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
TEST(FrSkySPORT, checkCrc)
|
||||
{
|
||||
// Packet downstream
|
||||
|
@ -516,4 +516,4 @@ TEST(FrSkySPORT, frskyCurrent)
|
|||
EXPECT_EQ(telemetryItems[0].valueMax, 505);
|
||||
}
|
||||
|
||||
#endif //#if defined(FRSKY_SPORT)
|
||||
#endif //#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
|
|
|
@ -78,11 +78,11 @@ inline void MIXER_RESET()
|
|||
|
||||
inline void TELEMETRY_RESET()
|
||||
{
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
memclear(&telemetryData, sizeof(telemetryData));
|
||||
TELEMETRY_RSSI() = 100;
|
||||
#endif
|
||||
#if defined(CPUARM) && defined(FRSKY)
|
||||
#if defined(CPUARM) && defined(TELEMETRY_FRSKY)
|
||||
for (int i=0; i<MAX_SENSORS; i++) {
|
||||
telemetryItems[i].clear();
|
||||
}
|
||||
|
|
|
@ -65,7 +65,7 @@ const pm_char STR_OPEN9X[] PROGMEM =
|
|||
ISTR(VFSWRESET)
|
||||
ISTR(FUNCSOUNDS)
|
||||
ISTR(VTELEMCHNS)
|
||||
#if defined(FRSKY) || defined(CPUARM)
|
||||
#if defined(TELEMETRY_FRSKY) || defined(CPUARM)
|
||||
ISTR(VTELEMUNIT)
|
||||
ISTR(VALARM)
|
||||
ISTR(VALARMFN)
|
||||
|
@ -130,7 +130,7 @@ const pm_char STR_OPEN9X[] PROGMEM =
|
|||
ISTR(VCELLINDEX)
|
||||
ISTR(VANTENNATYPES)
|
||||
#endif
|
||||
#if defined(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
ISTR(MAVLINK_BAUDS)
|
||||
ISTR(MAVLINK_AC_MODES)
|
||||
ISTR(MAVLINK_AP_MODES)
|
||||
|
@ -258,7 +258,7 @@ const pm_char STR_BLOFFBRIGHTNESS[] PROGMEM = TR_BLOFFBRIGHTNESS;
|
|||
const pm_char STR_SPLASHSCREEN[] PROGMEM = TR_SPLASHSCREEN;
|
||||
const pm_char STR_THROTTLEWARNING[] PROGMEM = TR_THROTTLEWARNING;
|
||||
const pm_char STR_SWITCHWARNING[] PROGMEM = TR_SWITCHWARNING;
|
||||
#ifdef FRSKY
|
||||
#ifdef TELEMETRY_FRSKY
|
||||
const pm_char STR_TIMEZONE[] PROGMEM = TR_TIMEZONE;
|
||||
const pm_char STR_ADJUST_RTC[] PROGMEM = TR_ADJUST_RTC;
|
||||
const pm_char STR_GPS[] PROGMEM = TR_GPS;
|
||||
|
@ -355,7 +355,7 @@ const pm_char STR_MENUCUSTOMFUNC[] PROGMEM = TR_MENUCUSTOMFUNC;
|
|||
const pm_char STR_MENUCUSTOMSCRIPTS[] PROGMEM = TR_MENUCUSTOMSCRIPTS;
|
||||
#endif
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
const pm_char STR_MENUTELEMETRY[] PROGMEM = TR_MENUTELEMETRY;
|
||||
const pm_char STR_LIMIT[] PROGMEM = TR_LIMIT;
|
||||
#endif
|
||||
|
@ -412,7 +412,7 @@ const pm_char STR_POWEROFF[] PROGMEM = TR_POWEROFF;
|
|||
|
||||
const pm_char STR_BATT_CALIB[] PROGMEM = TR_BATT_CALIB;
|
||||
|
||||
#if defined(CPUARM) || defined(FRSKY)
|
||||
#if defined(CPUARM) || defined(TELEMETRY_FRSKY)
|
||||
const pm_char STR_VOLTAGE[] PROGMEM = TR_VOLTAGE;
|
||||
const pm_char STR_CURRENT[] PROGMEM = TR_CURRENT;
|
||||
#endif
|
||||
|
@ -686,7 +686,7 @@ const pm_char STR_MODEL_SELECT[] PROGMEM = TR_MODEL_SELECT;
|
|||
const pm_char STR_MODULE_RANGE[] PROGMEM = TR_MODULE_RANGE;
|
||||
#endif
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#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;
|
||||
|
|
|
@ -141,7 +141,7 @@ extern const pm_char STR_OPEN9X[];
|
|||
#define OFS_VFSWRESET (OFS_VFSWFUNC + sizeof(TR_VFSWFUNC))
|
||||
#define OFS_FUNCSOUNDS (OFS_VFSWRESET + sizeof(TR_VFSWRESET))
|
||||
#define OFS_VTELEMCHNS (OFS_FUNCSOUNDS + sizeof(TR_FUNCSOUNDS))
|
||||
#if defined(FRSKY) || defined(CPUARM)
|
||||
#if defined(TELEMETRY_FRSKY) || defined(CPUARM)
|
||||
#if defined(CPUARM)
|
||||
#define OFS_VTELEMUNIT (OFS_VTELEMCHNS + sizeof(TR_VTELEMCHNS))
|
||||
#define OFS_VALARM (OFS_VTELEMUNIT + sizeof(TR_VTELEMUNIT))
|
||||
|
@ -231,7 +231,7 @@ extern const pm_char STR_OPEN9X[];
|
|||
#else
|
||||
#define OFS_MAVLINK_BAUDS (OFS_VTRAINERMODES)
|
||||
#endif
|
||||
#if defined(MAVLINK)
|
||||
#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))
|
||||
|
@ -273,7 +273,7 @@ extern const pm_char STR_OPEN9X[];
|
|||
#define STR_FUNCSOUNDS (STR_OPEN9X + OFS_FUNCSOUNDS)
|
||||
#define STR_VTELEMCHNS (STR_OPEN9X + OFS_VTELEMCHNS)
|
||||
|
||||
#if defined(FRSKY) || defined(CPUARM)
|
||||
#if defined(TELEMETRY_FRSKY) || defined(CPUARM)
|
||||
#if defined(CPUARM)
|
||||
#define STR_VTELEMUNIT (STR_OPEN9X + OFS_VTELEMUNIT)
|
||||
#define STR_VOLTSRC (STR_OPEN9X + OFS_VOLTSRC)
|
||||
|
@ -359,7 +359,7 @@ extern const pm_char STR_OPEN9X[];
|
|||
#define STR_VANTENNATYPES (STR_OPEN9X + OFS_VANTENNATYPES)
|
||||
#endif
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#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)
|
||||
|
@ -611,7 +611,7 @@ extern const pm_char STR_SENSOR[];
|
|||
extern const pm_char STR_COUNTRYCODE[];
|
||||
#endif
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
extern const pm_char STR_LIMIT[];
|
||||
#endif
|
||||
|
||||
|
@ -632,7 +632,7 @@ extern const pm_char STR_POWEROFF[];
|
|||
|
||||
extern const pm_char STR_BATT_CALIB[];
|
||||
|
||||
#if defined(CPUARM) || defined(FRSKY)
|
||||
#if defined(CPUARM) || defined(TELEMETRY_FRSKY)
|
||||
extern const pm_char STR_VOLTAGE[];
|
||||
extern const pm_char STR_CURRENT[];
|
||||
#endif
|
||||
|
@ -975,7 +975,7 @@ extern const pm_char STR_BLCOLOR[];
|
|||
extern const pm_char STR_MODULE_RANGE[];
|
||||
#endif
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#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[];
|
||||
|
|
|
@ -348,7 +348,7 @@
|
|||
|
||||
#define LEN_VFSWRESET TR("\004", "\012")
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
#define TR_FSW_RESET_TELEM TR("Telm", "Telemetrie")
|
||||
#else
|
||||
#define TR_FSW_RESET_TELEM
|
||||
|
@ -458,7 +458,7 @@
|
|||
#endif
|
||||
|
||||
#define LEN_VARIOSRC "\004"
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
#define TR_VARIOSRC "VSpd""A1\0 ""A2\0 ""dTE\0"
|
||||
#else
|
||||
#define TR_VARIOSRC "Alt\0""Alt+""VSpd""A1\0 ""A2\0"
|
||||
|
@ -586,7 +586,7 @@
|
|||
#define LEN_VFAILSAFE "\012"
|
||||
#define TR_VFAILSAFE "Nenastaven""Držet\0 ""Vlastní\0 ""Bez pulzů\0""Přijímač\0"
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
#define LEN_MAVLINK_BAUDS "\006"
|
||||
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""76800 ""115200"
|
||||
#define LEN_MAVLINK_AC_MODES "\011"
|
||||
|
@ -1064,7 +1064,7 @@
|
|||
#define TR_CONFIRMRESET "Smazat modely a nastavení?"
|
||||
#define TR_TO_MANY_LUA_SCRIPTS "Příliš mnoho skriptů!"
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#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"
|
||||
|
|
|
@ -354,7 +354,7 @@
|
|||
|
||||
#define LEN_VFSWRESET TR("\004", "\011")
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
#define TR_FSW_RESET_TELEM TR("Telm", "Telemetrie")
|
||||
#else
|
||||
#define TR_FSW_RESET_TELEM
|
||||
|
@ -464,7 +464,7 @@
|
|||
#endif
|
||||
|
||||
#define LEN_VARIOSRC "\004"
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
#define TR_VARIOSRC "Vspd""A1\0 ""A2\0 ""dTE\0"
|
||||
#else
|
||||
#define TR_VARIOSRC "Alt\0""Alt+""Vspd""A1\0 ""A2\0 "
|
||||
|
@ -602,7 +602,7 @@
|
|||
#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(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
#define LEN_MAVLINK_BAUDS "\006"
|
||||
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""76800 ""115200"
|
||||
#define LEN_MAVLINK_AC_MODES "\011"
|
||||
|
@ -1083,7 +1083,7 @@
|
|||
#define TR_CONFIRMRESET "ALLE Modelle + Einst. löschen?"
|
||||
#define TR_TO_MANY_LUA_SCRIPTS "Zu viele Lua-Scripte!!"
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#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"
|
||||
|
|
|
@ -355,7 +355,7 @@
|
|||
|
||||
#define LEN_VFSWRESET TR("\004", "\011")
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
#define TR_FSW_RESET_TELEM TR("Telm", "Telemetry")
|
||||
#else
|
||||
#define TR_FSW_RESET_TELEM
|
||||
|
@ -465,7 +465,7 @@
|
|||
#endif
|
||||
|
||||
#define LEN_VARIOSRC "\004"
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
#define TR_VARIOSRC "VSpd""A1\0 ""A2\0 ""dTE\0"
|
||||
#else
|
||||
#define TR_VARIOSRC "Alt\0""Alt+""VSpd""A1\0 ""A2\0"
|
||||
|
@ -603,7 +603,7 @@
|
|||
#define LEN_VFAILSAFE "\011"
|
||||
#define TR_VFAILSAFE "Not set\0 ""Hold\0 ""Custom\0 ""No pulses""Receiver\0"
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
#define LEN_MAVLINK_BAUDS "\006"
|
||||
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""76800 ""115200"
|
||||
#define LEN_MAVLINK_AC_MODES "\011"
|
||||
|
@ -1089,7 +1089,7 @@
|
|||
#define TR_CONFIRMRESET "Erase ALL models and settings?"
|
||||
#define TR_TO_MANY_LUA_SCRIPTS "Too many Lua scripts!"
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#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"
|
||||
|
|
|
@ -348,7 +348,7 @@
|
|||
|
||||
#define LEN_VFSWRESET TR("\004", "\011")
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
#define TR_FSW_RESET_TELEM TR("Telm", "Telemetry")
|
||||
#else
|
||||
#define TR_FSW_RESET_TELEM
|
||||
|
@ -458,7 +458,7 @@
|
|||
#endif
|
||||
|
||||
#define LEN_VARIOSRC "\005"
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
#define TR_VARIOSRC "Vario""A1\0 ""A2\0"
|
||||
#else
|
||||
#define TR_VARIOSRC "Alti\0""Alti+""Vario""A1\0 ""A2\0"
|
||||
|
@ -571,7 +571,7 @@
|
|||
#define LEN_VFAILSAFE "\011"
|
||||
#define TR_VFAILSAFE "Not set\0 ""Guardar\0 ""Adaptar\0 ""Sin pulso""Receiver\0"
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
#define LEN_MAVLINK_BAUDS "\006"
|
||||
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""76800 ""115200"
|
||||
#define LEN_MAVLINK_AC_MODES "\011"
|
||||
|
@ -1028,7 +1028,7 @@
|
|||
#define TR_CONFIRMRESET "Erase ALL models and settings?"
|
||||
#define TR_TO_MANY_LUA_SCRIPTS "Too many Lua scripts!"
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#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"
|
||||
|
|
|
@ -348,7 +348,7 @@
|
|||
|
||||
#define LEN_VFSWRESET TR("\004", "\011")
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
#define TR_FSW_RESET_TELEM TR("Telm", "Telemetry")
|
||||
#else
|
||||
#define TR_FSW_RESET_TELEM
|
||||
|
@ -458,7 +458,7 @@
|
|||
#endif
|
||||
|
||||
#define LEN_VARIOSRC "\005"
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
#define TR_VARIOSRC "Vario""A1\0 ""A2\0"
|
||||
#else
|
||||
#define TR_VARIOSRC "Alti\0""Alti+""Vario""A1\0 ""A2\0"
|
||||
|
@ -571,7 +571,7 @@
|
|||
#define LEN_VFAILSAFE "\011"
|
||||
#define TR_VFAILSAFE "Not set\0 ""Hold\0 ""Custom\0 ""No pulses""Receiver\0"
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
#define LEN_MAVLINK_BAUDS "\006"
|
||||
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""76800 ""115200"
|
||||
#define LEN_MAVLINK_AC_MODES "\011"
|
||||
|
@ -1028,7 +1028,7 @@
|
|||
#define TR_CONFIRMRESET "Erase ALL models and settings?"
|
||||
#define TR_TO_MANY_LUA_SCRIPTS "Too many Lua scripts!"
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#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"
|
||||
|
|
|
@ -350,7 +350,7 @@
|
|||
|
||||
#define LEN_VFSWRESET TR("\004", "\012")
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
#define TR_FSW_RESET_TELEM TR("Télm", "Télémesure")
|
||||
#else
|
||||
#define TR_FSW_RESET_TELEM
|
||||
|
@ -460,7 +460,7 @@
|
|||
#endif
|
||||
|
||||
#define LEN_VARIOSRC "\005"
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
#define TR_VARIOSRC "Vario""A1\0 ""A2\0 ""dTE\0 "
|
||||
#else
|
||||
#define TR_VARIOSRC "Alti\0""Alti+""Vario""A1\0 ""A2\0"
|
||||
|
@ -585,7 +585,7 @@
|
|||
#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(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
#define LEN_MAVLINK_BAUDS "\006"
|
||||
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""76800 ""115200"
|
||||
#define LEN_MAVLINK_AC_MODES "\011"
|
||||
|
@ -1060,7 +1060,7 @@
|
|||
#define TR_CONFIRMRESET "Effacer TOUS modèles/réglages?"
|
||||
#define TR_TO_MANY_LUA_SCRIPTS "Trop de scripts lua!"
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#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"
|
||||
|
|
|
@ -350,7 +350,7 @@
|
|||
|
||||
#define LEN_VFSWRESET TR("\004", "\011")
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
#define TR_FSW_RESET_TELEM TR("Telm", "Telemetr.")
|
||||
#else
|
||||
#define TR_FSW_RESET_TELEM
|
||||
|
@ -460,7 +460,7 @@
|
|||
#endif
|
||||
|
||||
#define LEN_VARIOSRC "\005"
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
#define TR_VARIOSRC "Vario""A1\0 ""A2\0"
|
||||
#else
|
||||
#define TR_VARIOSRC "Alti\0""Alti+""Vario""A1\0 ""A2\0"
|
||||
|
@ -585,7 +585,7 @@
|
|||
#define LEN_VFAILSAFE "\013"
|
||||
#define TR_VFAILSAFE "Non settato""Mantieni\0 ""Personali\0 ""No impulsi\0""Ricevente\0 "
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
#define LEN_MAVLINK_BAUDS "\006"
|
||||
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""76800 ""115200"
|
||||
#define LEN_MAVLINK_AC_MODES "\011"
|
||||
|
@ -1063,7 +1063,7 @@
|
|||
#define TR_CONFIRMRESET "Resettare TUTTI i dati?"
|
||||
#define TR_TO_MANY_LUA_SCRIPTS "Troppi Scripts Lua!"
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#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"
|
||||
|
|
|
@ -351,7 +351,7 @@
|
|||
|
||||
#define LEN_VFSWRESET TR("\004", "\012")
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
#define TR_FSW_RESET_TELEM TR("Telm", "Telemetrie")
|
||||
#else
|
||||
#define TR_FSW_RESET_TELEM
|
||||
|
@ -461,7 +461,7 @@
|
|||
#endif
|
||||
|
||||
#define LEN_VARIOSRC "\004"
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
#define TR_VARIOSRC "VSpd""A1\0 ""A2\0 ""dTE\0"
|
||||
#else
|
||||
#define TR_VARIOSRC "Alt\0""Alt+""VSpd""A1\0 ""A2\0"
|
||||
|
@ -590,7 +590,7 @@
|
|||
#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(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
#define LEN_MAVLINK_BAUDS "\006"
|
||||
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""76800 ""115200"
|
||||
#define LEN_MAVLINK_AC_MODES "\011"
|
||||
|
@ -1077,7 +1077,7 @@
|
|||
#define TR_CONFIRMRESET "Wis ALLE modellen en instellingen?"
|
||||
#define TR_TO_MANY_LUA_SCRIPTS "Te veel Lua scripts!"
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#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"
|
||||
|
|
|
@ -352,7 +352,7 @@
|
|||
|
||||
#define LEN_VFSWRESET TR("\004", "\011") /*9 decimal*/
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
#define TR_FSW_RESET_TELEM TR("Telm", "Telemetra")
|
||||
#else
|
||||
#define TR_FSW_RESET_TELEM
|
||||
|
@ -462,7 +462,7 @@
|
|||
#endif
|
||||
|
||||
#define LEN_VARIOSRC "\004"
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
#define TR_VARIOSRC "VSpd""A1\0 ""A2\0 ""dTE\0"
|
||||
#else
|
||||
#define TR_VARIOSRC "Wys\0""Wys+""VSpd""A1\0 ""A2\0"
|
||||
|
@ -587,7 +587,7 @@
|
|||
#define LEN_VFAILSAFE "\011" /*9 decimal*/
|
||||
#define TR_VFAILSAFE "Brak \0 ""Utrzymuj\0""Własne \0""0 sygnału""Odbiornik"
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
#define LEN_MAVLINK_BAUDS "\006"
|
||||
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""76800 ""115200"
|
||||
#define LEN_MAVLINK_AC_MODES "\011" /*9 decimal*/
|
||||
|
@ -1065,7 +1065,7 @@
|
|||
#define TR_CONFIRMRESET "WYkasować wszytkie modele? "
|
||||
#define TR_TO_MANY_LUA_SCRIPTS "Za dużo skryptów Lua!"
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#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"
|
||||
|
|
|
@ -343,7 +343,7 @@
|
|||
|
||||
#define LEN_VFSWRESET TR("\004", "\011")
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
#define TR_FSW_RESET_TELEM TR("Telm", "Telemetry")
|
||||
#else
|
||||
#define TR_FSW_RESET_TELEM
|
||||
|
@ -453,7 +453,7 @@
|
|||
#endif
|
||||
|
||||
#define LEN_VARIOSRC "\005"
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
#define TR_VARIOSRC "Vario""A1\0 ""A2\0"
|
||||
#else
|
||||
#define TR_VARIOSRC "Alti\0""Alti+""Vario""A1\0 ""A2\0"
|
||||
|
@ -566,7 +566,7 @@
|
|||
#define LEN_VFAILSAFE "\011"
|
||||
#define TR_VFAILSAFE "Not set\0 ""Hold\0 ""Custom\0 ""No pulses""Receiver\0"
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
#define LEN_MAVLINK_BAUDS "\006"
|
||||
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""76800 ""115200"
|
||||
#define LEN_MAVLINK_AC_MODES "\011"
|
||||
|
@ -1023,7 +1023,7 @@
|
|||
#define TR_CONFIRMRESET "Erase ALL models and settings?"
|
||||
#define TR_TO_MANY_LUA_SCRIPTS "Too many Lua scripts!"
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#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"
|
||||
|
|
|
@ -348,7 +348,7 @@
|
|||
|
||||
#define LEN_VFSWRESET TR("\004", "\011")
|
||||
|
||||
#if defined(FRSKY)
|
||||
#if defined(TELEMETRY_FRSKY)
|
||||
#define TR_FSW_RESET_TELEM TR("Telm", "Telemetry")
|
||||
#else
|
||||
#define TR_FSW_RESET_TELEM
|
||||
|
@ -458,7 +458,7 @@
|
|||
#endif
|
||||
|
||||
#define LEN_VARIOSRC "\005"
|
||||
#if defined(FRSKY_SPORT)
|
||||
#if defined(TELEMETRY_FRSKY_SPORT)
|
||||
#define TR_VARIOSRC "Vario""A1\0 ""A2\0"
|
||||
#else
|
||||
#define TR_VARIOSRC "Alti\0""Alti+""Vario""A1\0 ""A2\0"
|
||||
|
@ -596,7 +596,7 @@
|
|||
#define LEN_VFAILSAFE "\011"
|
||||
#define TR_VFAILSAFE "Ej givet""Lås Servo""Anpassat\0""Pulsfritt""Mottagare"
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#if defined(TELEMETRY_MAVLINK)
|
||||
#define LEN_MAVLINK_BAUDS "\006"
|
||||
#define TR_MAVLINK_BAUDS "4800 ""9600 ""14400 ""19200 ""38400 ""57600 ""76800 ""115200"
|
||||
#define LEN_MAVLINK_AC_MODES "\011"
|
||||
|
@ -1076,7 +1076,7 @@
|
|||
#define TR_CONFIRMRESET "Erase ALL models and settings?"
|
||||
#define TR_TO_MANY_LUA_SCRIPTS "För många Lua-scripts!"
|
||||
|
||||
#if defined(MAVLINK)
|
||||
#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"
|
||||
|
|
|
@ -70,7 +70,7 @@ void varioWakeup()
|
|||
}
|
||||
}
|
||||
|
||||
#elif defined(FRSKY)
|
||||
#elif defined(TELEMETRY_FRSKY)
|
||||
|
||||
void varioWakeup()
|
||||
{
|
||||
|
|
|
@ -66,14 +66,14 @@ elif options[optcount] == "9xr128":
|
|||
board_family = BOARD_FAMILY_AVR
|
||||
elif options[optcount] == "gruvin9x":
|
||||
command_options["PCB"] = "GRUVIN9X"
|
||||
command_options["EXT"] = "FRSKY"
|
||||
command_options["TELEMETRY"] = "FRSKY"
|
||||
firmware_options = options_gruvin9x
|
||||
maxsize = 65536 * 4
|
||||
board = BOARD_GRUVIN9X
|
||||
board_family = BOARD_FAMILY_AVR
|
||||
elif options[optcount] == "mega2560":
|
||||
command_options["PCB"] = "MEGA2560"
|
||||
command_options["EXT"] = "FRSKY"
|
||||
command_options["TELEMETRY"] = "FRSKY"
|
||||
firmware_options = options_mega2560
|
||||
maxsize = 65536 * 4
|
||||
board = BOARD_GRUVIN9X
|
||||
|
|
|
@ -3,7 +3,7 @@
|
|||
# The commands used to compare 2.2 flash usage
|
||||
# on 2.1 release: make PCB=9X EXT=FRSKY VOICE=YES AUDIO=YES AUTOSOURCE=YES AUTOSWITCH=YES HELI=YES TEMPLATES=YES GAUGES=NO
|
||||
# => 64818 (program) + 3236 (data)
|
||||
# on 2.2 release: cmake -DPCB=9X -DEXT=FRSKY -DAUDIO=YES -DVOICE=YES -DHELI=YES -DTEMPLATES=YES ~/git/opentx
|
||||
# on 2.2 release: cmake -DPCB=9X -DTELEMETRY=FRSKY -DAUDIO=YES -DVOICE=YES -DHELI=YES -DTEMPLATES=YES ~/git/opentx
|
||||
# => 64828 (program) + 3236 (data)
|
||||
|
||||
import os
|
||||
|
|
|
@ -26,12 +26,12 @@ tts_avr = {
|
|||
}
|
||||
|
||||
options_9x_ext = {
|
||||
"nmea": ("EXT", "NMEA", None),
|
||||
"frsky": ("EXT", "FRSKY", None),
|
||||
"telemetrez": ("EXT", "TELEMETREZ", None),
|
||||
"jeti": ("EXT", "JETI", None),
|
||||
"ardupilot": ("EXT", "ARDUPILOT", None),
|
||||
"mavlink": ("EXT", "MAVLINK", None),
|
||||
"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 = {
|
||||
|
|
|
@ -13,14 +13,19 @@ cd build
|
|||
|
||||
# OpenTX on 9X stock with FrSky telemetry
|
||||
rm -rf *
|
||||
cmake ${COMMON_OPTIONS} -DPCB=9X -DHELI=YES -DEXT=FRSKY ${SRCDIR}
|
||||
cmake ${COMMON_OPTIONS} -DPCB=9X -DHELI=YES -DTELEMETRY=FRSKY ${SRCDIR}
|
||||
make -j2 firmware
|
||||
make -j2 simu
|
||||
make -j2 gtests ; ./gtests
|
||||
|
||||
# OpenTX on 9X stock with Mavlink telemetry
|
||||
# OpenTX on 9X stock with Ardupilot telemetry
|
||||
rm -rf *
|
||||
cmake ${COMMON_OPTIONS} -DPCB=9X -DHELI=YES -DEXT=MAVLINK ${SRCDIR}
|
||||
cmake ${COMMON_OPTIONS} -DPCB=9X -DHELI=YES -DTELEMETRY=ARDUPILOT ${SRCDIR}
|
||||
make -j2 firmware
|
||||
|
||||
# OpenTX on 9X stock with JETI telemetry
|
||||
rm -rf *
|
||||
cmake ${COMMON_OPTIONS} -DPCB=9X -DHELI=YES -DTELEMETRY=JETI ${SRCDIR}
|
||||
make -j2 firmware
|
||||
|
||||
# OpenTX on Mega2560
|
||||
|
@ -32,7 +37,7 @@ make -j2 gtests ; ./gtests
|
|||
|
||||
# OpenTX on Mega2560 with Mavlink telemetry
|
||||
rm -rf *
|
||||
cmake ${COMMON_OPTIONS} -DPCB=MEGA2560 -DEXT=MAVLINK -DHELI=YES -DAUDIO=YES -DVOICE=YES ${SRCDIR}
|
||||
cmake ${COMMON_OPTIONS} -DPCB=MEGA2560 -DTELEMETRY=MAVLINK -DHELI=YES -DAUDIO=YES -DVOICE=YES ${SRCDIR}
|
||||
make -j2 firmware
|
||||
make -j2 simu
|
||||
make -j2 gtests ; ./gtests
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue