diff --git a/docs/Board - MatekF405.md b/docs/Board - MatekF405.md index 55a16ac7a5..bebdabab92 100644 --- a/docs/Board - MatekF405.md +++ b/docs/Board - MatekF405.md @@ -84,7 +84,6 @@ Soft serial is available as an alternative to a hardware UART on RX4/TX4. By def * Enable soft serial * Do not assign any function to hardware UART 4 * Assign the desired function to the soft-serial port -* Enable inversion if required `set telemetry_inversion = ON` (e.g. for Frsky telemetry) ### USB diff --git a/docs/Cli.md b/docs/Cli.md index e4b77382f1..5f0542c31b 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -200,7 +200,7 @@ Re-apply any new defaults as desired. | serialrx_inverted | OFF | Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY). | | spektrum_sat_bind | 0 | 0 = disabled. Used to bind the spektrum satellite to RX | | telemetry_switch | OFF | Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed. | -| telemetry_inversion | ON | Determines if the telemetry signal is inverted (Futaba, FrSKY). Only suitable on F3 uarts and Softserial on all targets | +| telemetry_inverted | OFF | Determines if the telemetry protocol default signal inversion is reversed. This should be OFF in most cases unless a custom or hacked RX is used. | | frsky_default_latitude | 0.000 | OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. | | frsky_default_longitude | 0.000 | OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. | | frsky_coordinates_format | 0 | FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA | diff --git a/docs/Telemetry.md b/docs/Telemetry.md index 1793e3fade..df5435ffab 100644 --- a/docs/Telemetry.md +++ b/docs/Telemetry.md @@ -36,19 +36,19 @@ Smartport uses _57600bps_ serial speed. ### Direct connection for F3/F7 -Only TX serial pin has to be connected to Smartport receiver. Enable the telemetry inversion setting. +Only TX serial pin has to be connected to Smartport receiver. Disable `telemetry_inverted`. ``` -set telemetry_inversion = ON +set telemetry_inverted = OFF set smartport_uart_unidir = OFF ``` ### Receiver univerted hack -Some receivers (X4R, XSR and so on) can be hacked to get _uninverted_ Smartport signal. In this case connect uninverted signal to TX pad of chosen serial port +Some receivers (X4R, XSR and so on) can be hacked to get _uninverted_ Smartport signal. In this case connect uninverted signal to TX pad of chosen serial port and enable `telemetry_inverted`. ``` -set telemetry_inversion = OFF +set telemetry_inverted = ON set smartport_uart_unidir = OFF ``` @@ -57,7 +57,7 @@ set smartport_uart_unidir = OFF Software emulated serial port allows to connect to Smartport receivers without any hacks. Only `TX` has to be connected to the receiver. ``` -set telemetry_inversion = ON +set telemetry_inverted = OFF ``` If solution above is not working, there is an alternative RX and TX lines have to be bridged using @@ -68,7 +68,7 @@ SmartPort ---> RX (CH5 pad) ---> 1kOhm resistor ---> TX (CH6 pad) ``` ``` -set telemetry_inversion = ON +set telemetry_inverted = OFF ``` ### SmartPort (S.Port) with external hardware inverter @@ -87,7 +87,7 @@ When external inverter is used, following configuration has to be applied: ``` set smartport_uart_unidir = ON -set telemetry_inversion = OFF +set telemetry_inverted = ON ``` ### Available SmartPort (S.Port) sensors @@ -132,15 +132,15 @@ FrSky telemetry is transmit only and just requires a single connection from the FrSky telemetry signals are inverted. To connect a INAV capable board to an FrSKy receiver you have some options. 1. A hardware inverter - Built in to some flight controllers. -2. Use software serial and enable frsky_inversion. -3. Use a flight controller that has software configurable hardware inversion (e.g. STM32F30x). +2. Use software serial. +3. Use a flight controller that has software configurable hardware inversion (e.g. F3 or F7). For 1, just connect your inverter to a usart or software serial port. For 2 and 3 use the CLI command as follows: ``` -set telemetry_inversion = ON +set telemetry_inverted = OFF ``` ### Precision setting for VFAS diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 15c83d244e..da2ade8cae 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1308,7 +1308,7 @@ groups: members: - name: telemetry_switch type: bool - - name: telemetry_inversion + - name: telemetry_inverted type: bool - name: frsky_default_latitude field: gpsNoFixLatitude @@ -1352,9 +1352,6 @@ groups: field: ltmUpdateRate condition: USE_TELEMETRY_LTM table: ltm_rates - - name: telemetry_halfduplex - field: halfDuplex - type: bool - name: PG_ELERES_CONFIG type: eleresConfig_t diff --git a/src/main/target/ALIENFLIGHTF4/config.c b/src/main/target/ALIENFLIGHTF4/config.c index 3ca3f140db..b7209d1c76 100644 --- a/src/main/target/ALIENFLIGHTF4/config.c +++ b/src/main/target/ALIENFLIGHTF4/config.c @@ -71,7 +71,6 @@ void targetConfiguration(void) } else { rxConfigMutable()->serialrx_provider = SERIALRX_SBUS; serialConfigMutable()->portConfigs[3].functionMask = FUNCTION_TELEMETRY_FRSKY; - telemetryConfigMutable()->telemetry_inversion = 0; featureConfigMutable()->enabledFeatures |= (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY); } diff --git a/src/main/target/ALIENFLIGHTNGF7/config.c b/src/main/target/ALIENFLIGHTNGF7/config.c index ba61701f18..905616fd32 100644 --- a/src/main/target/ALIENFLIGHTNGF7/config.c +++ b/src/main/target/ALIENFLIGHTNGF7/config.c @@ -73,7 +73,6 @@ void targetConfiguration(void) } else { rxConfigMutable()->serialrx_provider = SERIALRX_SBUS; serialConfigMutable()->portConfigs[3].functionMask = FUNCTION_TELEMETRY_FRSKY; - telemetryConfigMutable()->telemetry_inversion = 0; featureConfigMutable()->enabledFeatures |= (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY); } diff --git a/src/main/target/KAKUTEF4/config.c b/src/main/target/KAKUTEF4/config.c index a755bf5b42..1da3155b09 100755 --- a/src/main/target/KAKUTEF4/config.c +++ b/src/main/target/KAKUTEF4/config.c @@ -36,6 +36,5 @@ void targetConfiguration(void) { serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; - telemetryConfigMutable()->telemetry_inversion = true; } #endif diff --git a/src/main/target/MATEKF405SE/config.c b/src/main/target/MATEKF405SE/config.c index aae55f5cdb..27d254478b 100644 --- a/src/main/target/MATEKF405SE/config.c +++ b/src/main/target/MATEKF405SE/config.c @@ -37,5 +37,4 @@ void targetConfiguration(void) mixerConfigMutable()->mixerMode = MIXER_AIRPLANE; // default mixer to Airplane serialConfigMutable()->portConfigs[7].functionMask = FUNCTION_TELEMETRY_SMARTPORT; - telemetryConfigMutable()->telemetry_inversion = 1; } \ No newline at end of file diff --git a/src/main/target/SPRACINGF3NEO/config.c b/src/main/target/SPRACINGF3NEO/config.c index 5db0c020cc..4a6f585e0e 100644 --- a/src/main/target/SPRACINGF3NEO/config.c +++ b/src/main/target/SPRACINGF3NEO/config.c @@ -37,7 +37,6 @@ void targetConfiguration(void) serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; // So Bluetooth users don't have to change anything. serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(GPS_UART)].functionMask = FUNCTION_GPS; - //telemetryConfigMutable()->telemetry_inversion = 1; //telemetryConfigMutable()->halfDuplex = 1; } #endif diff --git a/src/main/target/SPRACINGF4EVO/config.c b/src/main/target/SPRACINGF4EVO/config.c index f6b053612b..96b5217206 100755 --- a/src/main/target/SPRACINGF4EVO/config.c +++ b/src/main/target/SPRACINGF4EVO/config.c @@ -32,6 +32,5 @@ void targetConfiguration(void) barometerConfigMutable()->baro_hardware = BARO_BMP280; 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()->telemetry_inversion = true; } #endif diff --git a/src/main/telemetry/frsky.c b/src/main/telemetry/frsky.c index 32f495b77d..a608f7cf5f 100644 --- a/src/main/telemetry/frsky.c +++ b/src/main/telemetry/frsky.c @@ -447,7 +447,7 @@ void configureFrSkyTelemetryPort(void) return; } - frskyPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_FRSKY, NULL, NULL, FRSKY_BAUDRATE, FRSKY_INITIAL_PORT_MODE, telemetryConfig()->telemetry_inversion ? SERIAL_INVERTED : SERIAL_NOT_INVERTED); + frskyPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_FRSKY, NULL, NULL, FRSKY_BAUDRATE, FRSKY_INITIAL_PORT_MODE, telemetryConfig()->telemetry_inverted ? SERIAL_NOT_INVERTED : SERIAL_INVERTED); if (!frskyPort) { return; } diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index a3e4d2a98f..14f6ab3246 100755 --- a/src/main/telemetry/smartport.c +++ b/src/main/telemetry/smartport.c @@ -296,7 +296,7 @@ static void freeSmartPortTelemetryPort(void) static void configureSmartPortTelemetryPort(void) { if (portConfig) { - portOptions_t portOptions = (telemetryConfig()->halfDuplex ? SERIAL_BIDIR : SERIAL_UNIDIR) | (telemetryConfig()->telemetry_inversion ? SERIAL_NOT_INVERTED : SERIAL_INVERTED); + portOptions_t portOptions = (telemetryConfig()->smartportUartUnidirectional ? SERIAL_UNIDIR : SERIAL_BIDIR) | (telemetryConfig()->telemetry_inverted ? SERIAL_NOT_INVERTED : SERIAL_INVERTED); smartPortSerialPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_SMARTPORT, NULL, NULL, SMARTPORT_BAUD, SMARTPORT_UART_MODE, portOptions); } diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c index 0f8d3f20b3..4a2053a438 100644 --- a/src/main/telemetry/telemetry.c +++ b/src/main/telemetry/telemetry.c @@ -49,19 +49,13 @@ #include "telemetry/ibus.h" #include "telemetry/crsf.h" -PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 0); - -#if defined(STM32F303xC) -#define TELEMETRY_DEFAULT_INVERSION 1 -#else -#define TELEMETRY_DEFAULT_INVERSION 0 -#endif +PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 1); PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, - .telemetry_inversion = TELEMETRY_DEFAULT_INVERSION, - .telemetry_switch = 0, .gpsNoFixLatitude = 0, .gpsNoFixLongitude = 0, + .telemetry_switch = 0, + .telemetry_inverted = 0, .frsky_coordinate_format = FRSKY_FORMAT_DMS, .frsky_unit = FRSKY_UNIT_METRICS, .frsky_vfas_precision = 0, @@ -71,7 +65,6 @@ PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, .smartportFuelUnit = SMARTPORT_FUEL_UNIT_MAH, .ibusTelemetryType = 0, .ltmUpdateRate = LTM_RATE_NORMAL, - .halfDuplex = 1, ); void telemetryInit(void) diff --git a/src/main/telemetry/telemetry.h b/src/main/telemetry/telemetry.h index a2b66483d8..19c70d4010 100644 --- a/src/main/telemetry/telemetry.h +++ b/src/main/telemetry/telemetry.h @@ -57,7 +57,7 @@ typedef struct telemetryConfig_s { float gpsNoFixLatitude; float 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_inversion; // also shared with smartport inversion + uint8_t telemetry_inverted; // Flip the default inversion of the protocol - Same as serialrx_inverted in rx.c, but for telemetry. frskyGpsCoordFormat_e frsky_coordinate_format; frskyUnit_e frsky_unit; uint8_t frsky_vfas_precision; @@ -67,7 +67,6 @@ typedef struct telemetryConfig_s { smartportFuelUnit_e smartportFuelUnit; uint8_t ibusTelemetryType; uint8_t ltmUpdateRate; - uint8_t halfDuplex; } telemetryConfig_t; PG_DECLARE(telemetryConfig_t, telemetryConfig);