Merge pull request #11320 from MrTucks/patch-2
[betaflight.git] / docs / Telemetry.md
blob1cf6b8f3b8cf98e66a434d2830b2c71d190c367f
1 # Telemetry
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 telemetry will only be enabled when armed on that port.
7 Telemetry is enabled using the 'TELEMETRY` feature.
9 ```
10 feature TELEMETRY
11 ```
13 Multiple telemetry providers are currently supported, FrSky, Graupner
14 HoTT V4, SmartPort (S.Port), LightTelemetry (LTM) and Ibus
16 All telemetry systems use serial ports, configure serial ports to use the telemetry system required.
18 ## FrSky telemetry
20 FrSky telemetry is transmit only and just requires a single connection from the TX pin of a serial port to the RX pin on an FrSky telemetry receiver.
22 FrSky telemetry signals are inverted.  To connect a Betaflight capable board to an FrSKy receiver you have some options.
24 1. A hardware inverter - Built in to some flight controllers.
25 2. Use software serial and enable frsky_inversion.
26 3. Use a flight controller that has software configurable hardware inversion (e.g. STM32F30x).
28 For 1, just connect your inverter to a usart or software serial port.
30 For 2 and 3 use the CLI command as follows:
32 ```
33 set tlm_inverted = ON
34 ```
37 ### Available sensors
39 The following sensors are transmitted :
41 | Name     | Description                                                                                            |
42 |----------|--------------------------------------------------------------------------------------------------------|
43 | Vspd     | vertical speed, unit is cm/s.                                                                          |
44 | Hdg      | heading, North is 0°, South is 180°.                                                                   |
45 | AccX,Y,Z | accelerometers values.                                                                                 |
46 | Tmp1     | baro temp if available, gyro otherwise.                                                                |
47 | RPM      | if armed, throttle value. battery capacity otherwise. (Blade number needs to be set to 12 in Taranis). |
48 | VFAS     | actual vbat value (see VFAS precision section bellow).                                                 |
49 | Curr     | actual current comsuption, in amp.                                                                     |
50 | Fuel     | if capacity set, remaining battery percentage mah drawn otherwise.                                     |
51 | GPS      | GPS coordinates.                                                                                       |
52 | Alt      | barometer based altitude, init level is zero.                                                          |
53 | Date     | time since powered.                                                                                    |
54 | GSpd     | current speed, calculated by GPS.                                                                      |
55 | GAlt     | GPS altitude, sea level is zero.                                                                       |
56 | Tmp2     | number of sats. Every second, a number > 100 is sent to represent GPS signal quality.                  |
57 | Cels     | average cell value, vbat divided by cell number.                                                       |
58 > Betaflight will send Cels (FLVSS Individual Cell Voltages Telemetry), disable the setting to use actual FLVSS sensor with:
59 > ```
60 > set telemetry_send_cells = OFF
61 > ```
63 > Note: cell voltage values are an assumed reputation of the cell voltage based on the packs voltage. Actual cell voltage may differ.
65 > To view individual cells or more importantly to get lowest cell (all cells are the sum of vbat, so each cell is the same in this case):
66 > See [OpenTX 2.1 & FrSky FLVSS Individual Cell Voltages](http://openrcforums.com/forum/viewtopic.php?t=7266).
67 > Add a new sensor, to display the lowest cell voltage set it up like this:
68 > - Type: Calculated
69 > - Formula: Cell
70 > - Cell Sensor: Cels _(pack total voltage, sum of all cells)_
71 > - Cell Index: Lowest
73 ### Precision setting for VFAS
75 Betaflight can send VFAS (FrSky Ampere Sensor Voltage) in two ways:
77 ```
78 set frsky_vfas_precision  = 0
79 ```
80 This is default setting which supports VFAS resolution of 0.2 volts and is supported on all FrSky hardware.
82 ```
83 set frsky_vfas_precision  = 1
84 ```
85 This is new setting which supports VFAS resolution of 0.1 volts and is only supported by OpenTX radios (this method uses custom ID 0x39).
89 ## HoTT telemetry
91 Only Electric Air Modules and GPS Modules are emulated.
93 Use the latest Graupner firmware for your transmitter and receiver.
95 Older HoTT transmitters required the EAM and GPS modules to be enabled in the telemetry menu of the transmitter. (e.g. on MX-20)
97 You can connect HoTT-Telemetry in two ways:
99 #### Old way:
100 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
101 a serial port should be connected using a diode and a single wire to the `T` port on a HoTT receiver.
103 Connect as follows:
105 * HoTT TX/RX `T` -> Serial RX (connect directly)
106 * HoTT TX/RX `T` -> Diode `-(  |)-` > Serial TX (connect via diode)
108 The diode should be arranged to allow the data signals to flow the right way
111 -(  |)- == Diode, | indicates cathode marker.
114 1N4148 diodes have been tested and work with the GR-24.
116 When using the diode disable `tlm_halfduplex`, go to CLI and type `set tlm_halfduplex = OFF`, don't forget a `save` afterwards.
118 #### New way:
119 You can use a single connection, connect HoTT RX/TX only to serial TX, leave serial RX open and make sure `tlm_halfduplex` is ON.
121 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.
123 Note: The SoftSerial ports may not be 5V tolerant on your board.  Verify if you require a 5v/3.3v level shifters.
125 ## LightTelemetry (LTM)
127 LTM is a lightweight streaming telemetry protocol supported by a
128 number of OSDs, ground stations and antenna trackers.
130 The Betaflight implementation of LTM implements the following frames:
132 * G-FRAME: GPS information (lat, long, ground speed, altitude, sat
133   info)
134 * A-FRAME: Attitude (pitch, roll, heading)
135 * S-FRAME: Status (voltage, current+, RSSI, airspeed+, status). Item
136   suffixed '+' not implemented in Betaflight.
137 * O-FRAME: Origin (home position, lat, long, altitude, fix)
139 In addition, in the inav (navigation-rewrite) fork:
140 * N-FRAME: Navigation information (GPS mode, Nav mode, Nav action,
141   Waypoint number, Nav Error, Nav Flags).
143 LTM is transmit only, and can work at any supported baud rate. It is
144 designed to operate over 2400 baud (9600 in Betaflight) and does not
145 benefit from higher rates. It is thus usable on soft serial.
147 More information about the fields, encoding and enumerations may be
148 found at
149 https://github.com/stronnag/mwptools/blob/master/docs/ltm-definition.txt
151 ## MAVLink telemetry
153 MAVLink is a very lightweight, header-only message marshalling library for micro air vehicles.
154 Betafight supports MAVLink for compatibility with ground stations, OSDs and antenna trackers built
155 for PX4, PIXHAWK, APM and Parrot AR.Drone platforms.
157 MAVLink implementation in Betaflight is transmit-only and usable on low baud rates and can be used over soft serial.
159 ## SmartPort (S.Port)
161 Smartport is a telemetry system used by newer FrSky transmitters and receivers such as the Taranis/XJR and X8R, X6R and X4R(SB).
163 More information about the implementation can be found here: https://github.com/frank26080115/cleanflight/wiki/Using-Smart-Port
165 ### Available sensors
167 The following sensors are transmitted :
169 | Name| Description|
170 | ----| -----------|
171 | A4 | average cell value. Warning : unlike FLVSS sensors, you do not get actual lowest value of a cell, but an average : (total lipo voltage) / (number of cells) |
172 | Alt | barometer based altitude, init level is zero. |
173 | Vspd | vertical speed, unit is cm/s. |
174 | Hdg | heading, North is 0°, South is 180°. |
175 | AccX,Y,Z | accelerometers values. |
176 | Tmp1 | actual flight mode, sent as 4 digits. Number is sent as (1)1234. Please ignore the leading 1, it is just there to ensure the number as always 5 digits (the 1 + 4 digits of actual data) the numbers are aditives (for example, if first digit after the leading 1 is 6, it means GPS Home and Headfree are both active) <ol><li>1 is GPS Hold, 2 is GPS Home, 4 is Headfree</li><li>1 is mag enabled, 2 is baro enabled, 4 is sonar enabled</li><li>3. 1 is angle, 2 is horizon, 4 is passthrough</li><li>4. 1 is ok to arm, 2 is arming is prevented,  4 is armed</li></ol> |
177 | Tmp2 | GPS lock status, Number is sent as 1234, the numbers are aditives<ol><li>1 is GPS Fix, 2 is GPS Home fix</li><li>HDOP (0-9, 0 is HDOP >= 5.5m, 9 is HDOP <= 1.0m)</li><li>number of sats</li><li>number of sats</li></ol> |
178 | VFAS | actual vbat value. |
179 | GAlt | GPS altitude, sea level is zero. |
180 | GSpd | current speed, calculated by GPS. |
181 | GPS | GPS coordinates. |
182 | 420 | GPS distance to home |
183 | Cels | average cell value, vbat divided by cell number. |
185 > Betaflight will send Cels (FLVSS Individual Cell Voltages Telemetry), disable the setting to use actual FLVSS sensor with:
186 > ```
187 > set report_cell_voltage = OFF
188 > ```
190 > Note: cell voltage values are an assumed reputation of the cell voltage based on the packs voltage. Actual cell voltage may differ. It is recommeded that you chain the flight controllers telemetry with a real Frsky FLVSS s.port sensor.
192 > To view individual cells or more importantly to get lowest cell (all cells are the sum of vbat, so each cell is the same in this case):
193 > See [OpenTX 2.1 & FrSky FLVSS Individual Cell Voltages](http://openrcforums.com/forum/viewtopic.php?t=7266).
194 > Add a new sensor, to display the lowest cell voltage set it up like this:
195 > - Type: Calculated
196 > - Formula: Cell
197 > - Cell Sensor: Cels _(pack total voltage, sum of all cells)_
198 > - Cell Index: Lowest
200 ### Integrate Betaflight telemetry with FrSky Smartport sensors
202 While Betaflight telemetry brings a lot of valuable data to the radio, there are additional sensors, like Lipo cells sensor FLVSS, that can be a great addition for many aircrafts. Smartport sensors are designed to be daisy chained, and CF telemetry is no exception to that. To add an external sensor, just connect the "S" port of the FC and sensor(s) together, and ensure the sensor(s) are getting connected to GND and VCC either from the controler or the receiver
204 ![Smartport diagram](assets/images/integrate_smartport.png)
206 ### SmartPort on F3 targets with hardware UART
208 Smartport devices can be connected directly to STM32F3 boards such as the SPRacingF3 and Sparky, with a single straight through cable without the need for any hardware modifications on the FC or the receiver. Connect the TX PIN of the UART to the Smartport signal pin.
210 For Smartport on F3 based boards, enable the telemetry inversion setting.
213 set tlm_inverted = ON
216 ### SmartPort on F1 and F3 targets with SoftSerial
218 Since F1 targets like Naze32 or Flip32 are not equipped with hardware inverters, SoftSerial might be simpler to use.
220 1. Enable SoftSerial ```feature SOFTSERIAL```
221 2. In Configurator assign _Telemetry_ > _Smartport_ > _Auto_ to SoftSerial port of your choice
222 3. Enable Telemetry ```feature TELEMETRY```
223 4. Confirm telemetry invesion ```set tlm_inverted = ON```
224 5. You have to bridge TX and RX lines of SoftSerial and connect them together to S.Port signal line in receiver
226 Notes:
228 * This has been tested with Flip32 and SPracingF3 boards and FrSky X8R and X4R receivers
229 * To discover all sensors board has to be armed, and when GPS is connected, it needs to have a proper 3D fix. When not armed, values like ***Vfas*** or GPS coordinates may not sent.
232 ## Ibus telemetry
234 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)
236 It shares 1 line for both TX and RX, the rx pin cannot be used for other serial port stuff.
237 It runs at a fixed baud rate of 115200.
240      _______
241     /       \                                             /---------\
242     | STM32 |--UART TX-->[Bi-directional @ 115200 baud]<--| IBUS RX |
243     |  uC   |--UART RX--x[not connected]                  \---------/
244     \_______/
247 It should be possible to daisy chain multiple sensors with ibus. This is implemented but not tested because i don't have one of the sensors to test with, the FC shall always be the last sensor in the chain.
249 It is possible to combine serial rx and ibus telemetry on the same uart pin on the flight controller, see [Rx](Rx.md).
251 ### Configuration
253 Ibus telemetry can be enabled in the firmware at build time using defines in target.h. It is enabled by default in those targets that have space left.
255 #define TELEMETRY
256 #define TELEMETRY_IBUS
259 CLI command to enable:
261 serial 1 1024 115200 57600 115200 115200
264 CLI setting to determine if the voltage reported is Vbatt or calculated average cell voltage
266 set report_cell_voltage=[ON/OFF]
269 ### Available sensors
271 The following sensors are transmitted :
273 Tmp1 : baro temp if available, gyro otherwise.
275 RPM : throttle value
277 Vbatt : configurable battery voltage or the average cell value, vbat divided by number of cells.
279 ### RX hardware ###
281 These receivers are reported to work with i-bus telemetry:
283 - FlySky/Turnigy FS-iA6B 6-Channel Receiver (http://www.flysky-cn.com/products_detail/&productId=51.html)
284 - FlySky/Turnigy FS-iA10B 10-Channel Receiver (http://www.flysky-cn.com/products_detail/productId=52.html)
287 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!
290 ## Jeti EX Bus telemetry
292 If telemetry is to be used, only the telemetry feature needs to be activated.
293 The telemetry names will be transmitted for the first 5-10 seconds.
295 The following values are available:
297 | Name            | Unit|
298 | --------------- | ----|
299 | Voltage         | [V]|
300 | Current         | [A]|
301 | Altitude        | [m]|
302 | Capacity        | [mAh]|
303 | Power           | [W]|
304 | Roll angle      | [°]|
305 | Pitch angle     | [°]|
306 | Heading         | [°]|
307 | Vario           | [m/s]|
308 | GPS Sats        | [1]|
309 | GPS Long        | |
310 | GPS Lat         | |
311 | GPS Speed       | [m/s]|
312 | GPS H-Distance  | [m]|
313 | GPS H-Direction | [°]|
314 | GPS Heading     | [°]|
315 | GPS Altitude    | [m]|
316 | G-Force X       | |
317 | G-Force Y       | |
318 | G-Force Z       | |
320 The telemetry values that are transmitted depend on whether a suitable sensor is available.
322 | Value                                       | Sensor |
323 | ------------------------------------------- | ------ |
324 | Voltage                                     | Voltage measurement|
325 | Current                                     | Current measurement|
326 | Capacity and Power                          | Voltage & Current Measurement|
327 | Heading                                     | Magnetometer|
328 | Altitude and Vario                          | Barometer|
329 | Roll angle, pitch angle and G-Froce X, Y, Z | ACC|
330 | GPS Sats, GPS...                            | GPS|