3 Telemetry allows you to know what is happening on your aircraft while you are flying it. Among other things you can receive battery voltages and GPS positions on your transmitter.
5 Telemetry can be either always on, or enabled when armed. If a serial port for telemetry is shared with other functionality then then telemetry will only be enabled when armed on that port.
7 Telemetry is enabled using the 'TELEMETRY' feature.
13 Multiple telemetry providers are currently supported, FrSky, Graupner HoTT V4, SmartPort (S.Port), LightTelemetry (LTM). MAVLink, IBUS, Crossfire and GSM SMS.
15 All telemetry systems use serial ports, configure serial ports to use the telemetry system required. Multiple telemetry streams may be enabled, but only one of each type, e.g. Smartport + LTM or MAVLink + CRSF.
17 ## SmartPort (S.Port) telemetry
19 Smartport is a telemetry system used by newer FrSky transmitters such as the Taranis Q X7, X9D, X9D+, X9E or XJR paired with X-series receivers such as the X4R(SB), X8R, XSR, R-XSR, XSR-M or XSR-E. For older D-series receivers see FrSky telemetry below.
21 More information about the implementation can be found here: https://github.com/frank26080115/cleanflight/wiki/Using-Smart-Port
23 Smartport devices are using _inverted_ serial protocol and as such can not be directly connected to all flight controllers. Depending on flight controller CPU family:
25 | CPU family | Direct connection | Receiver _uninverted_ hack | SoftwareSerial | Additional hardware inverter |
26 | ----- | ----- | ----- | ----- | ----- |
27 | STM32F4 | not possible (*) | possible | possible | possible |
28 | STM32F7 | possible | not required | possible | not required |
29 | STM32H7 | possible | not required | possible | not required |
31 > * possible if flight controller has dedicated, additional, hardware inverter
33 Smartport uses _57600bps_ serial speed.
35 ### Direct connection for F7/H7
37 Only TX serial pin has to be connected to Smartport receiver.
40 set telemetry_inverted = OFF
41 set telemetry_halfduplex = ON
44 ### Receiver uninverted hack
46 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`.
49 set telemetry_inverted = ON
50 set telemetry_halfduplex = ON
55 Software emulated serial port allows to connect to Smartport receivers without any hacks. Only `TX` has to be connected to the receiver.
58 set telemetry_inverted = OFF
59 set telemetry_halfduplex = ON
62 If the solution above is not working, there is an alternative RX and TX lines have to be bridged using
63 1kOhm resistor (confirmed working with 100Ohm, 1kOhm and 10kOhm)
66 SmartPort ---> RX (CH5 pad) ---> 1kOhm resistor ---> TX (CH6 pad)
70 set telemetry_inverted = OFF
73 ### SmartPort (S.Port) with external hardware inverter
75 It is possible to use DIY UART inverter to connect SmartPort receivers to F1 and F4 based flight controllers. This method does not require a hardware hack of S.Port receiver.
77 #### SmartPort inverter using bipolar transistors
78 ![Inverter](assets/images/smartport_inverter.png)
80 #### SmartPort inverter using unipolar transistors
81 ![Inverter](assets/images/smartport_inverter_2n7000.png)
83 **Warning** Chosen UART has to be 5V tolerant. If not, use 3.3V power supply instead (not tested)
85 When the external inverter is used, following configuration has to be applied:
88 set telemetry_halfduplex = OFF
89 set telemetry_inverted = ON
92 ### Available SmartPort (S.Port) sensors
94 The following sensors are transmitted
96 * **GSpd** : current horizontal ground speed, calculated by GPS.
97 * **VFAS** : actual vbat value.
98 * **Curr** : actual current comsuption, in amps.
99 * **Alt** : barometer based altitude, relative to home location.
100 * **Fuel** : if `smartport_fuel_unit = PERCENT` remaining battery percentage sent, MAH drawn otherwise.
101 * **GPS** : GPS coordinates.
102 * **VSpd** : vertical speed, unit is cm/s.
103 * **Hdg** : heading, North is 0°, South is 180°.
104 * **AccX,Y,Z** : accelerometer values (not sent if `frsky_pitch_roll = ON`).
105 * **470** : 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) :
106 * **A** : 1 = flaperon mode, 2 = auto tune mode, 4 = failsafe mode
107 * **B** : 1 = return to home, 2 = waypoint mode, 4 = headfree mode
108 * **C** : 1 = heading hold, 2 = altitude hold, 4 = position hold
109 * **D** : 1 = angle mode, 2 = horizon mode, 4 = passthru mode
110 * **E** : 1 = ok to arm, 2 = arming is prevented, 4 = armed
112 _NOTE_ This sensor used to be **Tmp1**. The ID has been reassigned in INAV 8.0. The old ID of **Tmp1** can still be used, by using `set frsky_use_legacy_gps_mode_sensor_ids = ON`. This is deprecated and will be removed in INAV 10.0. All tools and scripts using the old IDs should be updated to use the new ID.
113 * **480** : GPS lock status, accuracy, home reset trigger, and number of satellites. Number is sent as **ABCD** detailed below. Typical minimum GPS 3D lock value is 3906 (GPS locked and home fixed, HDOP highest accuracy, 6 satellites).
114 * **A** : 1 = GPS fix, 2 = GPS home fix, 4 = home reset (numbers are additive)
115 * **B** : GPS accuracy based on HDOP (0 = lowest to 9 = highest accuracy)
116 * **C** : number of satellites locked (digit C & D are the number of locked satellites)
117 * **D** : number of satellites locked (if 14 satellites are locked, C = 1 & D = 4)
119 _NOTE_ This sensor used to be **Tmp2**. The ID has been reassigned in INAV 8.0. The old ID of **Tmp2** can still be used, by using `set frsky_use_legacy_gps_mode_sensor_ids = ON`. This is deprecated and will be removed in INAV 10.0. All tools and scripts using the old IDs should be updated to use the new ID.
120 * **GAlt** : GPS altitude, sea level is zero.
121 * **ASpd** : true air speed, from pitot sensor. This is _Knots * 10_
122 * **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)
123 * **0420** : distance to GPS home fix, in meters
124 * **0430** : if `frsky_pitch_roll = ON` set this will be pitch degrees*10
125 * **0440** : if `frsky_pitch_roll = ON` set this will be roll degrees*10
126 * **0450** : 'Flight Path Vector' or 'Course over ground' in degrees*10
127 * **0460** : Azimuth in degrees*10
128 ### Compatible SmartPort/INAV telemetry flight status
130 To quickly and easily monitor these SmartPort sensors and flight modes, install [OpenTX Telemetry Widget](https://github.com/iNavFlight/OpenTX-Telemetry-Widget) to your Taranis Q X7, X9D, X9D+ or X9E transmitter.
135 Many of the same SmartPort telemetry values listed above are also sent with FrSky D-Series telemetry.
137 RPM shows throttle output when armed.
138 RPM shows when disarmed.
139 RPM requires that the 'blades' setting is set to 12 on your receiver/display - tested with Taranis/OpenTX.
143 Only Electric Air Modules and GPS Modules are emulated.
145 Use the latest Graupner firmware for your transmitter and receiver.
147 Older HoTT transmitters required the EAM and GPS modules to be enabled in the telemetry menu of the transmitter. (e.g. on MX-20)
149 You can use a single connection, connect HoTT RX/TX only to serial TX, leave serial RX open and make sure the setting `telemetry_halfduplex` is OFF.
151 The following information is deprecated, use only for compatibility:
152 Serial ports use two wires but HoTT uses a single wire so some electronics are required so that the signals don't get mixed up. The TX and RX pins of
153 a serial port should be connected using a diode and a single wire to the `T` port on a HoTT receiver.
157 * HoTT TX/RX `T` -> Serial RX (connect directly)
158 * HoTT TX/RX `T` -> Diode `-( |)-` > Serial TX (connect via diode)
160 The diode should be arranged to allow the data signals to flow the right way
163 -( |)- == Diode, | indicates cathode marker.
166 1N4148 diodes have been tested and work with the GR-24.
168 When using the diode enable `telemetry_halfduplex`, go to CLI and type `set telemetry_halfduplex = ON`, don't forget a `save` afterwards.
170 As noticed by Skrebber the GR-12 (and probably GR-16/24, too) are based on a PIC 24FJ64GA-002, which has 5V tolerant digital pins.
172 Note: The SoftSerial ports may not be 5V tolerant on your board. Verify if you require a 5v/3.3v level shifters.
174 ## LightTelemetry (LTM)
176 LTM is a lightweight streaming telemetry protocol supported by a number of OSDs, ground stations and antenna trackers.
178 The INAV implementation of LTM implements the following frames:
180 * G-FRAME: GPS information (lat, long, ground speed, altitude, sat info)
181 * A-FRAME: Attitude (pitch, roll, heading)
182 * S-FRAME: Status (voltage, current+, RSSI, airspeed+, status). Item suffixed '+' not implemented in INAV.
183 * O-FRAME: Origin (home position, lat, long, altitude, fix)
185 In addition, in INAV:
187 * N-FRAME: Navigation information (GPS mode, Nav mode, Nav action, Waypoint number, Nav Error, Nav Flags).
188 * X-FRAME: Extra information. Currently HDOP is reported.
190 LTM is transmit only, and can work at any supported baud rate. It is designed to operate over 2400 baud (9600 in INAV) and does not benefit from higher rates. It is thus usable on soft serial.
192 A CLI variable `ltm_update_rate` may be used to configure the update rate and hence band-width used by LTM, with the following enumerations:
194 * NORMAL: Legacy rate, currently 303 bytes/second (requires 4800 bps)
195 * MEDIUM: 164 bytes/second (requires 2400 bps)
196 * SLOW: 105 bytes/second (requires 1200 bps)
198 For many telemetry devices, there is direction correlation between the air-speed of the radio link and range; thus a lower value may facilitate longer range links.
200 More information about the fields, encoding and enumerations may be found [on the wiki](https://github.com/iNavFlight/inav/wiki/Lightweight-Telemetry-(LTM)).
205 MAVLink is a lightweight header-only message marshalling library for micro air vehicles. INAV supports MAVLink for compatibility with ground stations, OSDs and antenna trackers built for PX4, PIXHAWK, APM and Parrot AR.Drone platforms.
207 MAVLink implementation in INAV is transmit-only and usable on low baud rates and can be used over soft serial (requires 19200 baud). MAVLink V1 and V2 are supported.
210 ## Cellular telemetry via text messages
212 INAV can use a SimCom SIM800 series cellular module to provide telemetry via text messages. Telemetry messages can be requested by calling the module's number or sending it a text message. The module can be set to transmit messages at regular intervals, or when an acceleration event is detected. A text message command can be used to put the flight controller into RTH mode.
214 The telemetry message looks like this:
216 12.34V 2.0A ALT:5 SPD:10/13.6 DIS:78/19833 HDG:16 SAT:21 SIG:9 ANG maps.google.com/?q=6FG22222%2B222
218 giving battery voltage, current, altitude (m), speed / average speed (m/s), distance to home / total traveled distance (m), heading (degrees), number of satellites, cellular signal strength, flight mode and GPS coordinates as a Google Maps link. `SIG` has a range of 0 -- 31, with a value of 10 or higher indicating a usable signal quality.
220 Transmission at regular intervals can be set by giving a string of flags in the CLI variable `sim_transmit_flags`: `T` - transmit continuously, `F` - transmit in failsafe mode, `A` - transmit when altitude is lower than `sim_low_altitude`, `G` - transmit when GPS signal quality is low. `A` only transmits in ALT HOLD, WAYPOINT, RTH, and FAILSAFE flight modes. The transmission interval is given by `sim_transmit_interval` and is 60 seconds by default.
222 Text messages sent to the module can be used to set the transmission flags during flight, or to issue a RTH command to the flight controller. If a message begins with `RTH` it toggles forced RTH on / off, otherwise it is taken as a value for `sim_transmit_flags`. Note that an empty message turns transmission off, setting all flags to zero.
224 Acceleration events are indicated at the beginning of the message as follows: `HIT!` indicates impact / high g event, `HIT` indicates landing / backwards acceleration event, `DROP` indicates freefall / low g event.
226 To receive acceleration event messages, set one or more of the acceleration event threshold CLI variables to a nonzero value, and use the `A` flag in `sim_transmit_flags`. `acc_event_threshold_high` is the threshold (in cm/s/s) for impact detection by high magnitude of acceleration. `acc_event_threshold_low` is the threshold for freefall detection by low magnitude of acceleration. `acc_event_threshold_neg_x` is the threshold for landing detection (for fixed wing models) by high magnitude of negative x axis acceleration.
231 Ibus telemetry requires a single connection from the TX pin of a bidirectional serial port to the Ibus sens pin on an FlySky telemetry receiver. (tested with fs-iA6B receiver, iA10 should work)
233 It shares 1 line for both TX and RX, the rx pin cannot be used for other serial port stuff.
234 It runs at a fixed baud rate of 115200, so it need hardware uart (softserial is limit to 19200).
238 | STM32 |-->UART TX-->[Bi-directional @ 115200 baud]-->| Flysky RX |
239 | uC |- UART RX--x[not connected] | IBUS-Sensor |
240 \_______/ \-------------/
242 It is possible to daisy chain multiple sensors with ibus, but telemetry sensor will be overwrite by value sensor.
243 In this case sensor should be connected to RX and FC to sensor.
246 / \ /---------\ /-------------\ /-------------\
247 | STM32 |-->UART TX-->[Bi-directional @ 115200 baud]-->| CVT-01 |-->|others sensor|-->| Flysky RX |
248 | uC |- UART RX--x[not connected] \---------/ \-------------/ | IBUS-Sensor |
249 \_______/ \-------------/
254 Ibus telemetry is default enabled in the all firmware.
255 IBUS telemetry is disabled on ALIENWIIF3, RMDO at build time using defines in target.h.
257 #undef TELEMETRY_IBUS
259 ### Available sensors
261 The following sensors are transmitted :
265 1.Internal voltage in volts (not usable).
267 2.Valtage sensor in volts (Voltage type).
269 3.If baro sensor is avaliable then return temperature from baro sensor in °C else return temperature from gyro sensor in °C (Temperatyre type).
273 5.Course in degree (Rpm type).
275 6.Current in ampers (Voltage type).
277 7.Altitude in meters (Voltage type).
279 8.Direction to home in degree (Rpm type).
281 9.Distance to home in meters(Rpm type).
283 10.GPS course in degree (Rpm type).
285 11.GPS altitude in meters (Rpm type).
287 12.Second part of Lattitude (Rpm type), for example 5678 (-12.3456789 N).
289 13.Second part of Longitude (Rpm type), for example 6789 (-123.4567891 E).
291 14.First part of Lattitude (Voltage type), for example -12.45 (-12.3456789 N).
293 15.First part of Longitude (Voltage type), for example -123.45 (-123.4567890 E).
295 16.GPS speed in km/h (Rpm type).
297 1.Transmitter voltage in volts (not usable).
299 1.Error percent in % (not usable).
301 Sensors from 8 to 16 are avaliable only if GPS is at built time.
303 STATUS (number of satelites AS #0, FIX AS 0, HDOP AS 0, Mode AS 0)
305 FIX: 1 is No, 2 is 2D, 3 is 3D, 6 is No+FixHome, 7 is 2D+FixHome, 8 is 3D+FixHome
307 HDOP: 0 is 0-9m, 8 is 80-90m, 9 is >90m
309 Mode: 0 - Passthrough, 1-Armed(rate), 2-Horizon, 3-Angle, 4-Waypoint, 5-AltHold, 6-PosHold, 7-Rth, 8-Launch, 9-Failsafe
311 Example: 12803 is 12 satelites, Fix3D, FixHome, 0-9m HDOP, Angle Mode
317 0.Standard sensor type are used (Temp,Rpm,ExtV). Each transmitter should support this. (FS-i6, FS-i6S).
319 1.This same as 0, but GPS ground speed (sensor 16) is of type Speed in km/h. (FS-i6 10ch_MOD_i6_Programmer_V1_5.exe from https://github.com/benb0jangles/FlySky-i6-Mod-).
321 2.This same as 1, but GPS altitude (sensor 11) is of type ALT in m. (FS-i6 10ch_Timer_MOD_i6_Programmer_V1_4.exe from https://github.com/benb0jangles/FlySky-i6-Mod-).
323 3.This same as 2, but each sensor have its own sensor id. (FS-i6 10ch_Mavlink_MOD_i6_Programmer_V1_.exe from https://github.com/benb0jangles/FlySky-i6-Mod-):
324 sensor 4 is of type S85,
325 sensor 5 is of type ACC_Z,
326 sensor 6 is of type CURRENT,
327 sensor 7 is of type ALT,
328 sensor 8 is of type HEADING,
329 sensor 9 is of type DIST,
330 sensor 10 is of type COG,
331 sensor 10 is of type GALT,
332 sensor 12 is of type GPS_LON,
333 sensor 13 is of type GPS_LAT,
334 sensor 14 is of type ACC_X,
335 sensor 15 is of type ACC_Y,
336 sensor 16 is of type SPEED.
338 4.This same as 3, but support 4 byte sensors. (fix_updater_03_16_21_33_1 from https://github.com/qba667/FlySkyI6/tree/master/release):
339 sensor 7 is 4byte ALT, 12 is PRESURE or PITOT_SPEED if avaliable, 13 is GPS_STATUS, 14 is 4byte GPS_LON, 15 is 4byte GPS_LAT.
340 This required a receiver with new firmware that support SNR, RSSI and long frames (For FS-IA6B since August 2016 or need upgrade to wersion 1.6 https://github.com/povlhp/FlySkyRxFirmware).
342 5.This same as 4, but sensor 3 is ARMED, 4 is MODE, 12 is CLIMB.
344 6.For hali9_updater_04_21_23_13.bin from https://www.rcgroups.com/forums/showthread.php?2486545-FlySky-FS-i6-8-channels-firmware-patch%21/page118 or https://github.com/benb0jangles/FlySky-i6-Mod-/tree/master/10ch%20qba667_hali9%20Updater sensor 4 is of type CURRENT, sensor 5 is of type HEADING, sensor 6 is of type COG, sensor 7 is of type CLIMB, sensor 8 is of type YAW, sensor 9 is of type DIST, sensor 10 is of type PRESURE or PITOT_SPEED if avaliable, sensor 11 is of type SPEED, sensor 12 is of type GPS_LAT, sensor 13 is of type GPS_LON, sensor 14 is of type GALT, sensor 15 is of type ALT, sensor 16 is of type S85.
346 7.This same as 6, but sensor 3 is GPS_STATUS, 10 is ARMED, 16 is MODE.
348 8.This same as 7, but sensor 10 (ARMED) is reversed.
350 131.This same as 3, but sensor 16 (type SPEED) is in m/s.
352 132.This same as 4, but sensor 16 (type SPEED) is in m/s.
354 133.This same as 5, but sensor 16 (type SPEED) is in m/s.
356 134.This same as 6, but sensor 11 (type SPEED) is in m/s.
358 135.This same as 7, but sensor 11 (type SPEED) is in m/s.
360 136.This same as 8, but sensor 11 (type SPEED) is in m/s.
364 These receivers are reported to work with i-bus telemetry:
366 - FlySky/Turnigy FS-iA6B 6-Channel Receiver (http://www.flysky-cn.com/products_detail/&productId=51.html)
367 - FlySky/Turnigy FS-iA10B 10-Channel Receiver (http://www.flysky-cn.com/products_detail/productId=52.html)
369 Note that the FlySky/Turnigy FS-iA4B 4-Channel Receiver (http://www.flysky-cn.com/products_detail/productId=46.html) seems to work but has a bug that might lose the binding, DO NOT FLY the FS-iA4B!
371 ### Use ibus RX and ibus telemetry on only one port.
375 A. For use only IBUS RX connect directly Flysky IBUS-SERVO to FC-UART-RX.
376 In configurator set RX on selected port, set receiver mode to RX_SERIAL and Receiver provider to IBUS.
378 B. For use only IBUS telemetry connect directly Flysky IBUS-SENS to FC-UART-TX.
379 In configurator set IBUS telemetry on selected port and enable telemetry feature.
381 C. For use RX IBUS and telemetry IBUS together connect Flysky IBUS-SERVO and IBUS-SENS to FC-UART-TX using schematic:
386 | Servo |---|<---\ +------------+
388 | Sensor |---[R]--*-------| Serial TX |
389 +---------+ +------------+
391 R = 10Kohm, Diode 1N4148 (connect cathode to IBUS-Servo of Flysky receiver).
393 In configurator set IBUS telemetry and RX on this same port, enable telemetry feature, set receiver mode to RX_SERIAL and Receiver provider to IBUS.
396 Schematic above work also for connect telemetry only, but not work for connect rx only - will stop FC.
399 ## Futaba SBUS2 telemetry
401 SBUS2 telemetry requires a single connection from the TX pin of a bidirectional serial port to the SBUS2 pin on a Futaba T-FHSS or FASSTest telemetry receiver. (tested T16IZ radio and R7108SB and R3204SB receivers)
403 It shares 1 line for both TX and RX, the rx pin cannot be used for other serial port stuff.
404 It runs at a fixed baud rate of 100000, so it needs a hardware uart capable of inverted signals. It is not available on F4 mcus.
409 | STM32 |-->UART TX-->[Bi-directional @ 100000 baud]-->| Futaba RX |
410 | uC |- UART RX--x[not connected] | SBUS2 port |
411 \_______/ \-------------/
414 For more information and sensor slot numbering, refer to [SBUS2 Documentation](SBUS2_telemetry.md)