From 48281c17c9ca019ff91bc55dda68a00d6e111424 Mon Sep 17 00:00:00 2001 From: mikeller Date: Mon, 18 Sep 2017 20:36:02 +1200 Subject: [PATCH] Renamed 'sbus_inversion' to 'serialrx_inverted' and applied it to all protocols. --- src/main/fc/settings.c | 2 +- src/main/rx/crsf.c | 2 +- src/main/rx/ibus.c | 2 +- src/main/rx/jetiexbus.c | 4 ++-- src/main/rx/rx.c | 2 +- src/main/rx/rx.h | 2 +- src/main/rx/sbus.c | 2 +- src/main/rx/spektrum.c | 2 +- src/main/rx/sumd.c | 2 +- src/main/rx/sumh.c | 2 +- src/main/rx/xbus.c | 2 +- src/main/target/ALIENFLIGHTF3/config.c | 2 +- src/main/target/ALIENFLIGHTF4/config.c | 2 +- src/main/target/ALIENFLIGHTNGF7/config.c | 2 +- src/main/target/ALIENWHOOP/config.c | 4 +--- src/main/target/FF_PIKOBLX/config.c | 2 +- src/main/target/RACEBASE/config.c | 2 +- src/main/target/SPRACINGF3NEO/config.c | 1 - src/main/target/SPRACINGF4EVO/config.c | 1 - src/main/target/TINYFISH/config.c | 2 +- 20 files changed, 19 insertions(+), 23 deletions(-) diff --git a/src/main/fc/settings.c b/src/main/fc/settings.c index 9fbdc1073e..33fb9230ec 100644 --- a/src/main/fc/settings.c +++ b/src/main/fc/settings.c @@ -369,7 +369,7 @@ const clivalue_t valueTable[] = { { "max_aux_channels", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, MAX_AUX_CHANNEL_COUNT }, PG_RX_CONFIG, offsetof(rxConfig_t, max_aux_channel) }, #ifdef SERIAL_RX { "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SERIAL_RX }, PG_RX_CONFIG, offsetof(rxConfig_t, serialrx_provider) }, - { "sbus_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, sbus_inversion) }, + { "serialrx_inverted", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, serialrx_inverted) }, #endif #ifdef USE_SPEKTRUM_BIND { "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, .config.minmax = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX}, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_sat_bind) }, diff --git a/src/main/rx/crsf.c b/src/main/rx/crsf.c index e06c6dc8d1..9d9707b934 100644 --- a/src/main/rx/crsf.c +++ b/src/main/rx/crsf.c @@ -268,7 +268,7 @@ bool crsfRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) crsfDataReceive, CRSF_BAUDRATE, CRSF_PORT_MODE, - CRSF_PORT_OPTIONS | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) + CRSF_PORT_OPTIONS | (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) ); return serialPort != NULL; diff --git a/src/main/rx/ibus.c b/src/main/rx/ibus.c index bf911e9340..ff09673b83 100755 --- a/src/main/rx/ibus.c +++ b/src/main/rx/ibus.c @@ -218,7 +218,7 @@ bool ibusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) ibusDataReceive, IBUS_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, - SERIAL_NOT_INVERTED | (rxConfig->halfDuplex || portShared ? SERIAL_BIDIR : 0) + (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex || portShared ? SERIAL_BIDIR : 0) ); #if defined(TELEMETRY) && defined(TELEMETRY_IBUS) diff --git a/src/main/rx/jetiexbus.c b/src/main/rx/jetiexbus.c index 4f13e61fbe..e910f4f7d2 100644 --- a/src/main/rx/jetiexbus.c +++ b/src/main/rx/jetiexbus.c @@ -74,7 +74,7 @@ // Serial driver for Jeti EX Bus receiver // #define JETIEXBUS_BAUDRATE 125000 // EX Bus 125000; EX Bus HS 250000 not supported -#define JETIEXBUS_OPTIONS (SERIAL_STOPBITS_1 | SERIAL_PARITY_NO | SERIAL_NOT_INVERTED) +#define JETIEXBUS_OPTIONS (SERIAL_STOPBITS_1 | SERIAL_PARITY_NO) #define JETIEXBUS_MIN_FRAME_GAP 1000 #define JETIEXBUS_CHANNEL_COUNT 16 // most Jeti TX transmit 16 channels @@ -607,7 +607,7 @@ bool jetiExBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfi jetiExBusDataReceive, JETIEXBUS_BAUDRATE, MODE_RXTX, - JETIEXBUS_OPTIONS | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) + JETIEXBUS_OPTIONS | (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) ); serialSetMode(jetiExBusPort, MODE_RX); return jetiExBusPort != NULL; diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 17481d29bc..98fc39bdc9 100644 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -124,7 +124,7 @@ void pgResetFn_rxConfig(rxConfig_t *rxConfig) .halfDuplex = 0, .serialrx_provider = SERIALRX_PROVIDER, .rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL, - .sbus_inversion = 1, + .serialrx_inverted = 0, .spektrum_bind_pin_override_ioTag = IO_TAG(SPEKTRUM_BIND_PIN), .spektrum_bind_plug_ioTag = IO_TAG(BINDPLUG_PIN), .spektrum_sat_bind = 0, diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index c702d385fc..4f51ef3fb6 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -117,7 +117,7 @@ PG_DECLARE_ARRAY(rxChannelRangeConfig_t, NON_AUX_CHANNEL_COUNT, rxChannelRangeCo typedef struct rxConfig_s { uint8_t rcmap[RX_MAPPABLE_CHANNEL_COUNT]; // mapping of radio channels to internal RPYTA+ order uint8_t serialrx_provider; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_RX_SERIAL first. - uint8_t sbus_inversion; // default sbus (Futaba, FrSKY) is inverted. Support for uninverted OpenLRS (and modified FrSKY) receivers. + uint8_t serialrx_inverted; // invert the serial RX protocol compared to it's default setting uint8_t halfDuplex; // allow rx to operate in half duplex mode on F4, ignored for F1 and F3. uint8_t rx_spi_protocol; // type of SPI RX protocol // nrf24: 0 = v202 250kbps. (Must be enabled by FEATURE_RX_NRF24 first.) diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index fadc2fa2be..3fc8003407 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -253,7 +253,7 @@ bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) sbusDataReceive, SBUS_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, - SBUS_PORT_OPTIONS | (rxConfig->sbus_inversion ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) + SBUS_PORT_OPTIONS | (rxConfig->serialrx_inverted ? 0 : SERIAL_INVERTED) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) ); #ifdef TELEMETRY diff --git a/src/main/rx/spektrum.c b/src/main/rx/spektrum.c index 5d4bad4ec6..5692689509 100644 --- a/src/main/rx/spektrum.c +++ b/src/main/rx/spektrum.c @@ -341,7 +341,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig spektrumDataReceive, SPEKTRUM_BAUDRATE, portShared || srxlEnabled ? MODE_RXTX : MODE_RX, - SERIAL_NOT_INVERTED | ((srxlEnabled || rxConfig->halfDuplex) ? SERIAL_BIDIR : 0) + (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | ((srxlEnabled || rxConfig->halfDuplex) ? SERIAL_BIDIR : 0) ); #ifdef TELEMETRY diff --git a/src/main/rx/sumd.c b/src/main/rx/sumd.c index 68432ce3d9..17273995a2 100644 --- a/src/main/rx/sumd.c +++ b/src/main/rx/sumd.c @@ -184,7 +184,7 @@ bool sumdInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) sumdDataReceive, SUMD_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, - SERIAL_NOT_INVERTED | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) + (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) ); #ifdef TELEMETRY diff --git a/src/main/rx/sumh.c b/src/main/rx/sumh.c index 750700f7ad..9655ef9365 100644 --- a/src/main/rx/sumh.c +++ b/src/main/rx/sumh.c @@ -133,7 +133,7 @@ bool sumhInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) bool portShared = false; #endif - sumhPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sumhDataReceive, SUMH_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, SERIAL_NOT_INVERTED); + sumhPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sumhDataReceive, SUMH_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0)); #ifdef TELEMETRY if (portShared) { diff --git a/src/main/rx/xbus.c b/src/main/rx/xbus.c index 188f6e56c7..2ae2845e3e 100644 --- a/src/main/rx/xbus.c +++ b/src/main/rx/xbus.c @@ -334,7 +334,7 @@ bool xBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) xBusDataReceive, baudRate, portShared ? MODE_RXTX : MODE_RX, - SERIAL_NOT_INVERTED | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) + (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) ); #ifdef TELEMETRY diff --git a/src/main/target/ALIENFLIGHTF3/config.c b/src/main/target/ALIENFLIGHTF3/config.c index a6341c2eec..5e8ec5d752 100644 --- a/src/main/target/ALIENFLIGHTF3/config.c +++ b/src/main/target/ALIENFLIGHTF3/config.c @@ -93,7 +93,7 @@ void targetConfiguration(void) parseRcChannels("TAER1234", rxConfigMutable()); } else { rxConfigMutable()->serialrx_provider = SERIALRX_SBUS; - rxConfigMutable()->sbus_inversion = 0; + rxConfigMutable()->serialrx_inverted = true; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIALRX_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY | FUNCTION_RX_SERIAL; telemetryConfigMutable()->telemetry_inverted = false; featureSet(FEATURE_TELEMETRY); diff --git a/src/main/target/ALIENFLIGHTF4/config.c b/src/main/target/ALIENFLIGHTF4/config.c index b13c52b3d5..565816e96a 100644 --- a/src/main/target/ALIENFLIGHTF4/config.c +++ b/src/main/target/ALIENFLIGHTF4/config.c @@ -63,7 +63,7 @@ void targetConfiguration(void) rxConfigMutable()->spektrum_sat_bind_autoreset = 1; } else { rxConfigMutable()->serialrx_provider = SERIALRX_SBUS; - rxConfigMutable()->sbus_inversion = 0; + rxConfigMutable()->serialrx_inverted = true; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIALRX_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY | FUNCTION_RX_SERIAL; telemetryConfigMutable()->telemetry_inverted = false; batteryConfigMutable()->voltageMeterSource = VOLTAGE_METER_ADC; diff --git a/src/main/target/ALIENFLIGHTNGF7/config.c b/src/main/target/ALIENFLIGHTNGF7/config.c index a5feb582d9..6193dad004 100644 --- a/src/main/target/ALIENFLIGHTNGF7/config.c +++ b/src/main/target/ALIENFLIGHTNGF7/config.c @@ -62,7 +62,7 @@ void targetConfiguration(void) rxConfigMutable()->spektrum_sat_bind_autoreset = 1; } else { rxConfigMutable()->serialrx_provider = SERIALRX_SBUS; - rxConfigMutable()->sbus_inversion = 0; + rxConfigMutable()->serialrx_inverted = true; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIALRX_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY | FUNCTION_RX_SERIAL; telemetryConfigMutable()->telemetry_inverted = false; batteryConfigMutable()->voltageMeterSource = VOLTAGE_METER_ADC; diff --git a/src/main/target/ALIENWHOOP/config.c b/src/main/target/ALIENWHOOP/config.c index b26d223626..1d67cb5536 100644 --- a/src/main/target/ALIENWHOOP/config.c +++ b/src/main/target/ALIENWHOOP/config.c @@ -77,9 +77,7 @@ void targetConfiguration(void) rxConfigMutable()->spektrum_sat_bind_autoreset = 1; parseRcChannels("TAER1234", rxConfigMutable()); #if defined(ALIENWHOOPF4) - rxConfigMutable()->sbus_inversion = 0; // TODO: what to do about F4 inversion? -#else - rxConfigMutable()->sbus_inversion = 1; // invert on F7 + rxConfigMutable()->serialrx_inverted = true; // TODO: what to do about F4 inversion? #endif beeperOffSet((BEEPER_BAT_CRIT_LOW | BEEPER_BAT_LOW | BEEPER_RX_SET) ^ BEEPER_GYRO_CALIBRATED); diff --git a/src/main/target/FF_PIKOBLX/config.c b/src/main/target/FF_PIKOBLX/config.c index a1e71d6fa8..e51091d5c3 100644 --- a/src/main/target/FF_PIKOBLX/config.c +++ b/src/main/target/FF_PIKOBLX/config.c @@ -59,7 +59,7 @@ void targetConfiguration(void) rxConfigMutable()->spektrum_sat_bind_autoreset = 1; #else serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_TELEMETRY_FRSKY; - rxConfigMutable()->sbus_inversion = 0; + rxConfigMutable()->serialrx_inverted = true; featureSet(FEATURE_TELEMETRY); #endif parseRcChannels("TAER1234", rxConfigMutable()); diff --git a/src/main/target/RACEBASE/config.c b/src/main/target/RACEBASE/config.c index 6da7077aed..b00357784e 100755 --- a/src/main/target/RACEBASE/config.c +++ b/src/main/target/RACEBASE/config.c @@ -28,7 +28,7 @@ void targetConfiguration(void) { - rxConfigMutable()->sbus_inversion = 0; + rxConfigMutable()->serialrx_inverted = true; rxConfigMutable()->rssi_scale = 19; rxConfigMutable()->serialrx_provider = SERIALRX_SBUS; } diff --git a/src/main/target/SPRACINGF3NEO/config.c b/src/main/target/SPRACINGF3NEO/config.c index 50757d0410..31fb0e6dda 100644 --- a/src/main/target/SPRACINGF3NEO/config.c +++ b/src/main/target/SPRACINGF3NEO/config.c @@ -51,7 +51,6 @@ void targetConfiguration(void) { barometerConfigMutable()->baro_hardware = BARO_DEFAULT; compassConfigMutable()->mag_hardware = MAG_DEFAULT; - rxConfigMutable()->sbus_inversion = true; serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; // So Bluetooth users don't have to change anything. serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = TELEMETRY_PROVIDER_DEFAULT; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(GPS_UART)].functionMask = FUNCTION_GPS; diff --git a/src/main/target/SPRACINGF4EVO/config.c b/src/main/target/SPRACINGF4EVO/config.c index 4c00c94f01..9e96f3edf6 100644 --- a/src/main/target/SPRACINGF4EVO/config.c +++ b/src/main/target/SPRACINGF4EVO/config.c @@ -34,7 +34,6 @@ void targetConfiguration(void) { barometerConfigMutable()->baro_hardware = BARO_DEFAULT; - rxConfigMutable()->sbus_inversion = 1; serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; // So SPRacingF3OSD users don't have to change anything. serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; telemetryConfigMutable()->halfDuplex = 0; diff --git a/src/main/target/TINYFISH/config.c b/src/main/target/TINYFISH/config.c index bc84c72542..411c8e0de3 100644 --- a/src/main/target/TINYFISH/config.c +++ b/src/main/target/TINYFISH/config.c @@ -44,7 +44,7 @@ void targetConfiguration(void) serialConfigMutable()->portConfigs[index].functionMask = FUNCTION_TELEMETRY_FRSKY | FUNCTION_RX_SERIAL; rxConfigMutable()->serialrx_provider = SERIALRX_SBUS; - rxConfigMutable()->sbus_inversion = 0; + rxConfigMutable()->serialrx_inverted = true; telemetryConfigMutable()->telemetry_inverted = true; } #endif