Skip to content

Commit

Permalink
Telemetry documentation changes/clarification for 2.0 (iNavFlight#3712)
Browse files Browse the repository at this point in the history
Documentation clarification for telemetry
  • Loading branch information
teckel12 authored and digitalentity committed Aug 7, 2018
1 parent ceec94b commit 05e0e94
Show file tree
Hide file tree
Showing 3 changed files with 17 additions and 15 deletions.
18 changes: 9 additions & 9 deletions docs/Cli.md
Original file line number Diff line number Diff line change
Expand Up @@ -205,16 +205,16 @@ After restoring it's always a good idea to `dump` or `diff` the settings once ag
| 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_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 |
| frsky_unit | METRIC | METRIC , IMPERIAL |
| frsky_vfas_precision | 0 | Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method |
| frsky_pitch_roll | OFF | Send pitch and roll degrees*10 instead of raw accelerometer telemetry for S.Port and FrSky D-Series telemetry |
| report_cell_voltage | OFF | |
| frsky_unit | METRIC | Not used? [METRIC/IMPERIAL] |
| frsky_default_latitude | 0.000 | D-Series telemetry only: 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 | D-Series telemetry only: 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 | D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA |
| frsky_vfas_precision | 0 | D-Series telemetry only: Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method |
| frsky_pitch_roll | OFF | S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data |
| smartport_fuel_unit | MAH | S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends precent). [PERCENT/MAH/MWH] |
| smartport_uart_unidir | OFF | S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details |
| report_cell_voltage | OFF | S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON |
| hott_alarm_sound_interval | 5 | Battery alarm delay in seconds for Hott telemetry |
| smartport_uart_unidir | OFF | Turn UART into UNIDIR for smartport telemetry for usage on F1 and F4 target. See Telemetry.md for details |
| smartport_fuel_unit | MAH | Unit of the value sent with the `FUEL` ID through the S.Port and FrSky D-Series telemetry. [PERCENT/MAH/MWH] |
| ibus_telemetry_type | 0 | Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details. |
| ltm_update_rate | NORMAL | Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details. |
| battery_capacity | 0 | Battery capacity in mAH. This value is used in conjunction with the current meter to determine remaining battery capacity. |
Expand Down
10 changes: 6 additions & 4 deletions docs/Telemetry.md
Original file line number Diff line number Diff line change
Expand Up @@ -98,11 +98,11 @@ The following sensors are transmitted
* **VFAS** : actual vbat value.
* **Curr** : actual current comsuption, in amps.
* **Alt** : barometer based altitude, relative to home location.
* **Fuel** : if `battery_capacity` variable set and variable `smartport_fuel_percent = ON` remaining battery percentage, mAh drawn otherwise.
* **Fuel** : if `smartport_fuel_unit = PERCENT` remaining battery percentage sent, MAH drawn otherwise.
* **GPS** : GPS coordinates.
* **VSpd** : vertical speed, unit is cm/s.
* **Hdg** : heading, North is 0°, South is 180°.
* **AccX,Y,Z** : accelerometer values.
* **AccX,Y,Z** : accelerometer values (not sent if `frsky_pitch_roll = ON`).
* **Tmp1** : flight mode, sent as 5 digits. Number is sent as **ABCDE** detailed below. The numbers are additives (for example: if digit C is 6, it means both position hold and altitude hold are active) :
* **A** : 1 = flaperon mode, 2 = auto tune mode, 4 = failsafe mode
* **B** : 1 = return to home, 2 = waypoint mode, 4 = headfree mode
Expand All @@ -118,6 +118,8 @@ The following sensors are transmitted
* **ASpd** : true air speed, from pitot sensor.
* **A4** : average cell value. Warning : unlike FLVSS and MLVSS sensors, you do not get actual lowest value of a cell, but an average : (total lipo voltage) / (number of cells)
* **0420** : distance to GPS home fix, in meters
* **0430** : if `frsky_pitch_roll = ON` set this will be pitch degrees*10
* **0440** : if `frsky_pitch_roll = ON` set this will be roll degrees*10

### Compatible SmartPort/INAV telemetry flight status

Expand Down Expand Up @@ -160,10 +162,10 @@ This is new setting which supports VFAS resolution of 0.1 volts and is supported

### Notes

Many of the same SmartPort telemetry values listed above are also sent with FrSky D-Series telemetry.

RPM shows throttle output when armed.
RPM shows when disarmed.
TEMP2 shows Satellite Signal Quality when GPS is enabled.

RPM requires that the 'blades' setting is set to 12 on your receiver/display - tested with Taranis/OpenTX.

## HoTT telemetry
Expand Down
4 changes: 2 additions & 2 deletions src/main/telemetry/smartport.c
Original file line number Diff line number Diff line change
Expand Up @@ -430,13 +430,13 @@ void processSmartPortTelemetry(smartPortPayload_t *payload, volatile bool *clear
smartPortSendPackage(id, attitude.values.yaw * 10); // given in 10*deg, requested in 10000 = 100 deg
*clearToSend = false;
break;
case FSSP_DATAID_PITCH :
case FSSP_DATAID_PITCH :
if (telemetryConfig()->frsky_pitch_roll) {
smartPortSendPackage(id, attitude.values.pitch); // given in 10*deg
*clearToSend = false;
}
break;
case FSSP_DATAID_ROLL :
case FSSP_DATAID_ROLL :
if (telemetryConfig()->frsky_pitch_roll) {
smartPortSendPackage(id, attitude.values.roll); // given in 10*deg
*clearToSend = false;
Expand Down

0 comments on commit 05e0e94

Please sign in to comment.