1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-17 05:15:25 +03:00

Removed 'tlm_switch', replaced with 'isModeActivationConditionPresent(BOXTELEMETRY)'.

This commit is contained in:
mikeller 2018-05-08 01:14:18 +12:00
parent 7b831f94ee
commit 19a360b867
6 changed files with 6 additions and 9 deletions

View file

@ -775,8 +775,8 @@ bool processRx(timeUs_t currentTimeUs)
#ifdef USE_TELEMETRY
if (feature(FEATURE_TELEMETRY)) {
if ((!telemetryConfig()->telemetry_switch && ARMING_FLAG(ARMED)) ||
(telemetryConfig()->telemetry_switch && IS_RC_MODE_ACTIVE(BOXTELEMETRY))) {
if ((!isModeActivationConditionPresent(BOXTELEMETRY) && ARMING_FLAG(ARMED)) ||
(isModeActivationConditionPresent(BOXTELEMETRY) && IS_RC_MODE_ACTIVE(BOXTELEMETRY))) {
releaseSharedTelemetryPorts();
} else {

View file

@ -246,7 +246,7 @@ void initActiveBoxIds(void)
BME(BOXOSD);
#ifdef USE_TELEMETRY
if (feature(FEATURE_TELEMETRY) && telemetryConfig()->telemetry_switch) {
if (feature(FEATURE_TELEMETRY)) {
BME(BOXTELEMETRY);
}
#endif

View file

@ -771,7 +771,6 @@ const clivalue_t valueTable[] = {
// PG_TELEMETRY_CONFIG
#ifdef USE_TELEMETRY
{ "tlm_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, telemetry_switch) },
{ "tlm_inverted", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, telemetry_inverted) },
{ "tlm_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, halfDuplex) },
#if defined(USE_TELEMETRY_FRSKY_HUB)

View file

@ -276,7 +276,7 @@ bool isSerialConfigValid(const serialConfig_t *serialConfigToCheck)
* rules:
* - 1 MSP port minimum, max MSP ports is defined and must be adhered to.
* - MSP is allowed to be shared with EITHER any telemetry OR blackbox.
* (using either / or, switching based on armed / disarmed or an AUX channel if 'telemetry_switch' is true
* (using either / or, switching based on armed / disarmed or the AUX channel configured for BOXTELEMETRY)
* - serial RX and FrSky / LTM / MAVLink telemetry can be shared
* (serial RX using RX line, telemetry using TX line)
* - No other sharing combinations are valid.

View file

@ -57,12 +57,11 @@
#include "telemetry/ibus.h"
#include "telemetry/msp_shared.h"
PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 1);
PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 2);
PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
.telemetry_inverted = false,
.halfDuplex = 1,
.telemetry_switch = 0,
.gpsNoFixLatitude = 0,
.gpsNoFixLongitude = 0,
.frsky_coordinate_format = FRSKY_FORMAT_DMS,
@ -120,7 +119,7 @@ bool telemetryDetermineEnabledState(portSharing_e portSharing)
bool enabled = portSharing == PORTSHARING_NOT_SHARED;
if (portSharing == PORTSHARING_SHARED) {
if (telemetryConfig()->telemetry_switch)
if (isModeActivationConditionPresent(BOXTELEMETRY))
enabled = IS_RC_MODE_ACTIVE(BOXTELEMETRY);
else
enabled = ARMING_FLAG(ARMED);

View file

@ -44,7 +44,6 @@ typedef enum {
typedef struct telemetryConfig_s {
int16_t gpsNoFixLatitude;
int16_t gpsNoFixLongitude;
uint8_t telemetry_switch; // Use aux channel to change serial output & baudrate( MSP / Telemetry ). It disables automatic switching to Telemetry when armed.
uint8_t telemetry_inverted;
uint8_t halfDuplex;
frskyGpsCoordFormat_e frsky_coordinate_format;