3 LTM was defined by "KipK" for the Ghetto Station antenna tracking project and originally implemented in Taulabs and Baseflight. It was adopted by INAV due to its excellent characteristics for low data rate / high update rate telemetry.
5 Since its introduction to INAV, a number of extension have been added; these are documented below, in addition to the original frames.
11 The LTM protocol starts with "$T", followed by a function byte, the payload and a simple CRC checksum. Its weakness is that there is no length parameter (so the receiver needs to know, apriori,the length for each function), and the single byte checksum is not as robust as the multi-byte checksum in for example the ublox GPS protocol. However, the high data rate ensures that good data should be delivered over occasional transmission errors. In practice, LTM is an excellent light weight telemetry solution.
18 | 3..n | n bytes payload |
21 LTM telemetry can be read by [Ghettostation](https://github.com/KipK/Ghettostation), [LTM Telemetry OLED ](https://github.com/sppnk/LTM-Telemetry-OLED) , [EZGUI](http://ez-gui.com/) , [MwpTools](https://github.com/stronnag/mwptools) and others.
23 LTM can provide good telemetry down to 2400 (5Hz attitude updates). Due to restrictions in INAV 1.2 and earlier, 9600 was the lowest baud rate supported, which gives 10Hz attitude and 5Hz GPS data. More recently (INAV 1.7.0), LTM is available from 1200 baud and higher; the data transmission frequency is automatically determined from the baud rate, but can be overridden by the user where the baud rate can support the required update frequency. See the [INAV Telemetry documentation](https://github.com/iNavFlight/inav/blob/master/docs/Telemetry.md#lighttelemetry-ltm) and [below](#inav-cli-support) for CLI settings.
25 The function consists of a single ASCII character, described below. Data is binary, little endian. The checksum is an XOR of the payload bytes.
27 The follow telemetry frames are supported:
29 | Function Byte | Usage | Frequency |
30 | ------------- | ----- | ---- |
31 | G | GPS Frame | 5Hhz at > 2400 baud |
32 | A | Attitude Frame | 10 Hz at > 2400 baud |
33 | S | Status Frame | 5Hhz at > 2400 baud |
34 | O | Origin Frame | 1 Hz rate |
35 | N | Navigation Frame (INAV extension) | ~4 Hz rate |
36 | X | GPS eXended data (INAV extension) | 1 Hz rate |
38 In addition, LTM is used by NRF24L01 / deviationtx INAV protocol, which defines an additional frame for in-TX tuning. This frame is not transmitted for telemetry.
40 | Function Byte | Usage |
41 | ------------- | ----- |
42 | T | Tuning frame (INAV extension) |
46 The payload is 14 bytes.
50 | Latitude | int32 decimal degrees * 10,000,000 (1E7) |
51 | Longitude | int32 decimal degrees * 10,000,000 (1E7) |
52 | Ground Speed | uchar m/s |
53 | Altitude | (u)int32, cm (m / 100). In the original specification, this was unsigned. In INAV it is signed and should be so interpreted by consumers |
54 | Sats | uchar. bits 0-1 : fix ; bits 2-7 : number of satellites |
58 The payload is 6 bytes
62 | Pitch | int16, degrees |
63 | Roll | int16, degrees |
64 | Heading | int16, degrees. Course over ground |
68 The payload is 7 bytes
73 | Battery Consumption | uint16, mAh |
75 | Airspeed | uchar, m/s |
78 Airspeed (vice GPS ground speed in the G-frame) requires INAV 1.7.2 or later, with `PITOT` defined at build time, and a detected pitot sensor.
80 The status byte is used as
86 | 2 - 7 | status, as (shifted value): |
95 | | Altitude Hold (8) |
103 | | Fly by wire A (16) |
104 | | Fly by wire B (17) |
110 As a general purpose protocol, not all status can be mapped to INAV modes.
112 (*) indicates INAV extension, post 2019-02-28
116 The payload is 14 bytes
120 | Latitude | int32 decimal degrees * 10,000,000 (1E7) |
121 | Longitude | int32 decimal degrees * 10,000,000 (1E7) |
122 | Altitude | uint32, cm (m / 100) [always 0 in INAV] |
123 | OSD on | uchar (always 1) |
124 | Fix | uchar, home fix status (0 == no fix) |
126 ## Navigation Frame (N)
128 The payload is 6 bytes. Note that this frame largely mirrors the Multiwii-nav `MSP_NAV_STATUS` message and this contains redundancies and values that are not used in INAV.
134 | Nav Action | uchar (not all used in inav) |
135 | Waypoint number | uchar, target waypoint |
136 | Nav Error | uchar |
137 | Flags | uchar (to be defined) |
141 | GPS mode | Enumeration |
142 | ----------- | -------- |
148 | Nav mode | Enumeration |
149 | ----------- | -------- |
153 | 3 | PosHold infinite |
154 | 4 | PosHold timed |
159 | 9 | Landing in Progress |
161 | 11 | Settling before landing |
162 | 12 | Start descent |
163 | 13 | Hover above home (INAV only) |
164 | 14 | Emergency landing (INAV only) |
165 | 15 | Critical GPS failure (yes 15, you never want to see this) |
167 Note that these values were defined by Multiwii-nav and not all are applicable to INAV.
169 | Nav Action | Enumeration |
170 | ----------- | -------- |
173 | 2 | POSHOLD_UNLIM |
181 | Nav Error | Enumeration |
182 | ----------- | -------- |
183 | 0 | Navigation system is working |
184 | 1 | Next waypoint distance is more than the safety limit, aborting mission |
185 | 2 | GPS reception is compromised - pausing mission |
186 | 3 | Error while reading next waypoint from memory, aborting mission |
187 | 4 | Mission Finished |
188 | 5 | Waiting for timed position hold |
189 | 6 | Invalid Jump target detected, aborting mission |
190 | 7 | Invalid Mission Step Action code detected, aborting mission |
191 | 8 | Waiting to reach return to home altitude |
192 | 9 | GPS fix lost, mission aborted |
193 | 10 | Disarmed, navigation engine disabled |
194 | 11 | Landing is in progress, check attitude |
196 ## GPS Extra Frame (X)
198 The payload is 6 bytes.
202 | HDOP | uint16 HDOP * 100 |
203 | hw status | uint8 |
204 | LTM_X_counter | uint8 |
205 | Disarm Reason | uint8 |
206 | (unused) | 1 byte |
208 Note that hw status (hardware sensor status) is INAV 1.5 and later. If the value is non-zero, then a sensor has failed.
209 A complementary update has been made to MSP_STATUS (https://github.com/iNavFlight/inav/wiki/INAV-MSP-frames-changelog).
210 Thus, on disarming, the sensor status may be evinced from the MSP_STATUS/sensor field.
212 The sensor hardware failure indication is backwards compatible with versions prior to 1.5 (and other Multiwii / Cleanflight derivatives).
214 The LTM_X_counter value is incremented each transmission and rolls over (modulo 256). It is intended to enable consumers to estimate packet loss.
218 LTM is transmit only, and can work at any supported baud rate. It was designed to operate over 2400 baud and does not benefit from (much) higher rates. It is thus usable on soft serial. The extra frames later introduced by INAV means that 4800 baud is required for the highest update rate.
220 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:
222 * NORMAL: Legacy rate, currently 303 bytes/second (requires 4800 bps)
223 * MEDIUM: 164 bytes/second (requires 2400 bps)
224 * SLOW: 105 bytes/second (requires 1200 bps)
226 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.
230 A couple of data samples are available from the [mwptools](https://github.com/stronnag/mwptools) project. [Sample1](https://raw.githubusercontent.com/wiki/stronnag/mwptools/data/ltm_2015-11-08.tar.gz) and [Sample2](https://raw.githubusercontent.com/wiki/stronnag/mwptools/data/mwp_2015-12-12-LTM.tar.gz) include raw dumps, structured data logs and READMEs explaining usage.
236 The payload is 12 bytes. This frame is not transmitted by INAV telemetry.
248 | rates-roll | uint8 |
249 | rates-pitch | uint8 |
250 | rates-yaw | uint8 |
252 ## Checksum Calculation
254 The checksum is a simple XOR over the payload. The following example (Python) illustrates the calculation of the checksum over the payload bytes:
257 def checksum(payload):