1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-13 11:29:56 +03:00

Replace telemetry_inversion with telemetry_inverted

telemetry_inverted applies to any telemetry protocol and causes
the default protocol inversion to be flipped. This means that a
default of 0 (OFF) will work for most users, while hacked and custom
RXs can be used by enabling this new setting.

The parameter group version for PG_TELEMETRY_CONFIG has been
increased to prevent the value from the old telemetry_inversion
setting to overwrite telemetry_inverted when upgrading from
previous versions.

Documention and target files have been updated too.
This commit is contained in:
Alberto García Hierro 2018-04-18 15:09:53 +01:00
parent f71a8cd90c
commit c402745514
14 changed files with 18 additions and 36 deletions

View file

@ -84,7 +84,6 @@ Soft serial is available as an alternative to a hardware UART on RX4/TX4. By def
* Enable soft serial * Enable soft serial
* Do not assign any function to hardware UART 4 * Do not assign any function to hardware UART 4
* Assign the desired function to the soft-serial port * Assign the desired function to the soft-serial port
* Enable inversion if required `set telemetry_inversion = ON` (e.g. for Frsky telemetry)
### USB ### USB

View file

@ -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). | | 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 | | 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_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_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_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 | | frsky_coordinates_format | 0 | FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA |

View file

@ -36,19 +36,19 @@ Smartport uses _57600bps_ serial speed.
### Direct connection for F3/F7 ### 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 set smartport_uart_unidir = OFF
``` ```
### Receiver univerted hack ### 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 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. 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 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 ### 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 smartport_uart_unidir = ON
set telemetry_inversion = OFF set telemetry_inverted = ON
``` ```
### Available SmartPort (S.Port) sensors ### 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. 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. 1. A hardware inverter - Built in to some flight controllers.
2. Use software serial and enable frsky_inversion. 2. Use software serial.
3. Use a flight controller that has software configurable hardware inversion (e.g. STM32F30x). 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 1, just connect your inverter to a usart or software serial port.
For 2 and 3 use the CLI command as follows: For 2 and 3 use the CLI command as follows:
``` ```
set telemetry_inversion = ON set telemetry_inverted = OFF
``` ```
### Precision setting for VFAS ### Precision setting for VFAS

View file

@ -1308,7 +1308,7 @@ groups:
members: members:
- name: telemetry_switch - name: telemetry_switch
type: bool type: bool
- name: telemetry_inversion - name: telemetry_inverted
type: bool type: bool
- name: frsky_default_latitude - name: frsky_default_latitude
field: gpsNoFixLatitude field: gpsNoFixLatitude
@ -1352,9 +1352,6 @@ groups:
field: ltmUpdateRate field: ltmUpdateRate
condition: USE_TELEMETRY_LTM condition: USE_TELEMETRY_LTM
table: ltm_rates table: ltm_rates
- name: telemetry_halfduplex
field: halfDuplex
type: bool
- name: PG_ELERES_CONFIG - name: PG_ELERES_CONFIG
type: eleresConfig_t type: eleresConfig_t

View file

@ -71,7 +71,6 @@ void targetConfiguration(void)
} else { } else {
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS; rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
serialConfigMutable()->portConfigs[3].functionMask = FUNCTION_TELEMETRY_FRSKY; serialConfigMutable()->portConfigs[3].functionMask = FUNCTION_TELEMETRY_FRSKY;
telemetryConfigMutable()->telemetry_inversion = 0;
featureConfigMutable()->enabledFeatures |= (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY); featureConfigMutable()->enabledFeatures |= (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY);
} }

View file

@ -73,7 +73,6 @@ void targetConfiguration(void)
} else { } else {
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS; rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
serialConfigMutable()->portConfigs[3].functionMask = FUNCTION_TELEMETRY_FRSKY; serialConfigMutable()->portConfigs[3].functionMask = FUNCTION_TELEMETRY_FRSKY;
telemetryConfigMutable()->telemetry_inversion = 0;
featureConfigMutable()->enabledFeatures |= (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY); featureConfigMutable()->enabledFeatures |= (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY);
} }

View file

@ -36,6 +36,5 @@
void targetConfiguration(void) void targetConfiguration(void)
{ {
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
telemetryConfigMutable()->telemetry_inversion = true;
} }
#endif #endif

View file

@ -37,5 +37,4 @@ void targetConfiguration(void)
mixerConfigMutable()->mixerMode = MIXER_AIRPLANE; // default mixer to Airplane mixerConfigMutable()->mixerMode = MIXER_AIRPLANE; // default mixer to Airplane
serialConfigMutable()->portConfigs[7].functionMask = FUNCTION_TELEMETRY_SMARTPORT; serialConfigMutable()->portConfigs[7].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
telemetryConfigMutable()->telemetry_inversion = 1;
} }

View file

@ -37,7 +37,6 @@ void targetConfiguration(void)
serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; // So Bluetooth users don't have to change anything. 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(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(GPS_UART)].functionMask = FUNCTION_GPS; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(GPS_UART)].functionMask = FUNCTION_GPS;
//telemetryConfigMutable()->telemetry_inversion = 1;
//telemetryConfigMutable()->halfDuplex = 1; //telemetryConfigMutable()->halfDuplex = 1;
} }
#endif #endif

View file

@ -32,6 +32,5 @@ void targetConfiguration(void)
barometerConfigMutable()->baro_hardware = BARO_BMP280; barometerConfigMutable()->baro_hardware = BARO_BMP280;
serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; // So SPRacingF3OSD users don't have to change anything. serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; // So SPRacingF3OSD users don't have to change anything.
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
telemetryConfigMutable()->telemetry_inversion = true;
} }
#endif #endif

View file

@ -447,7 +447,7 @@ void configureFrSkyTelemetryPort(void)
return; 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) { if (!frskyPort) {
return; return;
} }

View file

@ -296,7 +296,7 @@ static void freeSmartPortTelemetryPort(void)
static void configureSmartPortTelemetryPort(void) static void configureSmartPortTelemetryPort(void)
{ {
if (portConfig) { 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); smartPortSerialPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_SMARTPORT, NULL, NULL, SMARTPORT_BAUD, SMARTPORT_UART_MODE, portOptions);
} }

View file

@ -49,19 +49,13 @@
#include "telemetry/ibus.h" #include "telemetry/ibus.h"
#include "telemetry/crsf.h" #include "telemetry/crsf.h"
PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 0); PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 1);
#if defined(STM32F303xC)
#define TELEMETRY_DEFAULT_INVERSION 1
#else
#define TELEMETRY_DEFAULT_INVERSION 0
#endif
PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
.telemetry_inversion = TELEMETRY_DEFAULT_INVERSION,
.telemetry_switch = 0,
.gpsNoFixLatitude = 0, .gpsNoFixLatitude = 0,
.gpsNoFixLongitude = 0, .gpsNoFixLongitude = 0,
.telemetry_switch = 0,
.telemetry_inverted = 0,
.frsky_coordinate_format = FRSKY_FORMAT_DMS, .frsky_coordinate_format = FRSKY_FORMAT_DMS,
.frsky_unit = FRSKY_UNIT_METRICS, .frsky_unit = FRSKY_UNIT_METRICS,
.frsky_vfas_precision = 0, .frsky_vfas_precision = 0,
@ -71,7 +65,6 @@ PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
.smartportFuelUnit = SMARTPORT_FUEL_UNIT_MAH, .smartportFuelUnit = SMARTPORT_FUEL_UNIT_MAH,
.ibusTelemetryType = 0, .ibusTelemetryType = 0,
.ltmUpdateRate = LTM_RATE_NORMAL, .ltmUpdateRate = LTM_RATE_NORMAL,
.halfDuplex = 1,
); );
void telemetryInit(void) void telemetryInit(void)

View file

@ -57,7 +57,7 @@ typedef struct telemetryConfig_s {
float gpsNoFixLatitude; float gpsNoFixLatitude;
float gpsNoFixLongitude; 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_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; frskyGpsCoordFormat_e frsky_coordinate_format;
frskyUnit_e frsky_unit; frskyUnit_e frsky_unit;
uint8_t frsky_vfas_precision; uint8_t frsky_vfas_precision;
@ -67,7 +67,6 @@ typedef struct telemetryConfig_s {
smartportFuelUnit_e smartportFuelUnit; smartportFuelUnit_e smartportFuelUnit;
uint8_t ibusTelemetryType; uint8_t ibusTelemetryType;
uint8_t ltmUpdateRate; uint8_t ltmUpdateRate;
uint8_t halfDuplex;
} telemetryConfig_t; } telemetryConfig_t;
PG_DECLARE(telemetryConfig_t, telemetryConfig); PG_DECLARE(telemetryConfig_t, telemetryConfig);