Updated _Sidebar (markdown)
[inav.wiki.git] / MSP-Navigation-Messages.md
blobec50775825bbe10b520b6d41e67c7dd12de4a0fc
1 # MSP NAV Protocol and Types
3 This document describes MSP navigation messages, their usage and implementation details. Both **inav** and **multiwii** implementations (which are largely the same) are documented in this article.
5 Note that all binary values are little endian (MSP standard).
7 # Implementation and versions
9 This document should match the inav 1.2 (and later) and Multiwii 2.5 flight controller firmware. The messages described are implemented in [mwp](https://github.com/stronnag/mwptools) (Linux / FreeBSD / Windows (Cygwin,WSL)), ezgui (Android) mission planners / ground station applications and "drone helper" (Windows 10) mission planner. mwp and ezgui support both iNav and Multiwii; WinGui is a legacy Windows / Multiwii only mission planner that also supports this message set. Prior to inav 3.0, the [inav-configurator](https://github.com/iNavFlight/inav-configurator) supported a subset of  MSP Waypoint (WP) types; for inav 3.0 it is intended to support all WP types.
11 # WayPoint and Action Attributes
13 Each  waypoint has a type and takes a number of parameters, as below. These are used in the MSP_WP message. The final column indicated if the message is implemented for inav 1.2 (and later).
15 | Value | Enum | P1 | P2 | P3 | Lat | Lon | Alt | iNav |
16 | ---- | ---- | ---- | ---- | ---- | ---- | ---- | ---- | ---- |
17 | 1 | WAYPOINT      | Speed (cm/s) [1] (exception [6]) | | Altitude Mode [7] | ✔ | ✔ | ✔ | ✔ |
18 | 2 | POSHOLD_UNLIM |          | | | ✔ | ✔ | ✔ | [5] |
19 | 3 | POSHOLD_TIME  | Wait time (seconds) | (speed (cm/s)[1]) | Altitude Mode [7] | ✔ | ✔ | ✔ | ✔ 2.5 and later |
20 | 4 | RTH [4]       | Land if non-zero | | |    |    | ✔ [2] | ✔ |
21 | 5 | SET_POI [3]   |          | | | ✔ | ✔ | | ✔ 2.6 and later |
22 | 6 | JUMP          | Target WP#      | No. of repeats (-1 = forever) | | | | | ✔ 2.5 and later |
23 | 7 | SET_HEAD [3]  | Heading  (degrees) | | | | | | ✔ 2.6 and later |
24 | 8 | LAND | Speed (cm/s) [1] | Elevation Adjustment (m) [8] | Altitude Mode [7] | ✔ | ✔ | ✔ | ✔ 2.5 and later |
26 1. Leg speed is an inav extension (for multi-rotors only). It is the speed on the leg terminated by the WP (so the speed for WP2 is used for the leg WP1 -> WP2) (cm/s).
27 2. Not used by inav
28 3. Once SET_HEAD or SET_POI is invoked, it remains active until cleared by SET_HEAD with a P1 value of -1.
29 4. If a mission contains multiple RTH stanzas, then for MultiWii, the mission terminates at the first RTH. For inav, prior to c. 2.6, the mission would continue if RTH-LAND is not set, and valid waypoints follow.
30 5. If the final entry in a mission is a WAYPOINT, the inav treats it as POSHOLD_UNLIM.
31 6. For inav's "follow-me" mode (WP#255, POSHOLD engaged), P1 may be used to send an orientation heading (0-359 degrees).
32 7. inav 3.0 and later, P3 defines the altitude mode. 0 (default, legacy) = Relative to Home, 1 = Absolute (AMSL). Ignored for releases prior to 3.0.
33 8. inav 3.0 and later, P2 defines the ground elevation (in metres) for the LAND WP. If the altitude mode is absolute, this is also absolute; for relative altitude, then it is the difference between the assumed home location and the LAND WP. Ignored for releases prior to 3.0.
35 ## Geospatial Units 
37 | Field | XML Mission File | MSP_WP binary message |
38 | ----- | ---------------- | --------------------- |
39 | Latitude, Longitude | Decimal degrees, WGS84 | Integer, WGS84 Degrees * 1E7 |
40 | Altitude | Integer Metres | Centimetres |
42 ## FlyBy Home Waypoints
44 From inav 3.1, "FlyBy Home" (FBH) waypoints are supported for WAYPOINT, POSHOLD_TIME and LAND. These WPs are designated by either (or both) of
45 * The latitude and longitude is zero; or
46 * The `flag` field is set to 0x48 (72d, 'H')
48 FBH waypoints have no defined location until the mission is executed, when they assume the location of the **arming** home location (not affected by `safehome`). This is ephemeral and is reset on each arming. The location uploaded to the FC is irrelevant where `flag == 0x48`; in such cases a subsequent download from the FC will return the original WP latitude and longitude, not the home used for a particular instance. 
50 ## Annotated Example
51 The following example, using the MW XML (ezgui, inav configurator, mwp) format, illustrates the WAYPOINT, JUMP, POSHOLD_TIME and LAND types:
52 ![Complex Mission](images/eg_complex_mission.png)
53 ```
54 <?xml version="1.0" encoding="utf-8"?>
55 <mission>
56   <missionitem no="1" action="WAYPOINT" lat="54.353319318038153" lon="-4.5179273723848077" alt="35" parameter1="0" parameter2="0" parameter3="0"></missionitem>
57   <missionitem no="2" action="WAYPOINT" lat="54.353572350395972" lon="-4.5193913118652516" alt="35" parameter1="0" parameter2="0" parameter3="0"></missionitem>
58   <missionitem no="3" action="WAYPOINT" lat="54.354454163955907" lon="-4.5196617811150759" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
59   <missionitem no="4" action="WAYPOINT" lat="54.354657830207479" lon="-4.5186895986330455" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
60   <missionitem no="5" action="JUMP" lat="0" lon="0" alt="0" parameter1="2" parameter2="2" parameter3="0"></missionitem>
61   <missionitem no="6" action="WAYPOINT" lat="54.354668848061756" lon="-4.5176009696657218" alt="35" parameter1="0" parameter2="0" parameter3="0"></missionitem>
62   <missionitem no="7" action="WAYPOINT" lat="54.354122567317191" lon="-4.5172673708680122" alt="35" parameter1="0" parameter2="0" parameter3="0"></missionitem>
63   <missionitem no="8" action="JUMP" lat="0" lon="0" alt="0" parameter1="1" parameter2="1" parameter3="0"></missionitem>
64   <missionitem no="9" action="POSHOLD_TIME" lat="54.353138333126651" lon="-4.5190405596657968" alt="35" parameter1="45" parameter2="0" parameter3="0"></missionitem>
65   <missionitem no="10" action="WAYPOINT" lat="54.354847022143616" lon="-4.518210497615712" alt="35" parameter1="0" parameter2="0" parameter3="0"></missionitem>
66   <missionitem no="11" action="LAND" lat="54.354052100964488" lon="-4.5178091504726012" alt="60" parameter1="0" parameter2="0" parameter3="0"></missionitem>
67 </mission>
68 ```
69 Mission points 5 and 8 are JUMP; they have no location as they affect the current location (the previous WP) and cause an action.
70 * After WP 4 (JUMP at 5), the vehicle will proceed to WP 2 (`parameter1 = 2`); it will do this twice (`parameter2 = 2`). Then it will proceed to WP 6.
71 * After WP 7 (JUMP at 8), the vehicle will proceed to WP 1 (`parameter1 = 1`); it will do this once (`parameter2 = 1`). Then it will proceed to WP 9.
72 * The second JUMP (8) will cause the first jump (5) to be re-executed.
74 Mission point 9 is POSHOLD_TIME. The vehicle will loiter for 45 seconds (`parameter1 = 45`) at the WP9 location. A multi-rotor will hold a steady position, fixed wing will fly in a circle as defined by the CLI parameter `nav_fw_loiter_radius`.
76 Mission point 11 is LAND. The vehicle will land (unconditionally, regardless of `nav_rth_allow_landing`) at the given location. The CLI setting `nav_disarm_on_landing` is honoured.
78 There is a video animation of the flight in [a short youtube video](https://youtu.be/MTA42WUOjUY) and a [more detailed youtube video tutorial](https://www.youtube.com/watch?v=w6M-v4qM5Yg). The mission is executed as:
80 | WP / next wp | Course |  Dist |  Total |
81 | ------------ | ------ | ----- | ------ |
82 | WP01 - WP02 | 287° |   99m |    99m |
83 | WP02 - WP03 | 350° |  100m |   198m |
84 | WP03 - WP04 | 070° |   67m |   265m |
85 | WP04 (J05) WP02 | 201° |  129m |   394m |
86 | WP02 - WP03 | 350° |  100m |   494m |
87 | WP03 - WP04 | 070° |   67m |   561m |
88 | WP04 (J05) WP02 | 201° |  129m |   690m |
89 | WP02 - WP03 | 350° |  100m |   789m |
90 | WP03 - WP04 | 070° |   67m |   856m |
91 | WP04 - WP06 | 089° |   71m |   927m |
92 | WP06 - WP07 | 160° |   64m |   991m |
93 | WP07 (J08) WP01 | 206° |   99m |  1090m |
94 | WP01 - WP02 | 287° |   99m |  1189m |
95 | WP02 - WP03 | 350° |  100m |  1288m |
96 | WP03 - WP04 | 070° |   67m |  1355m |
97 | WP04 (J05) WP02 | 201° |  129m |  1484m |
98 | WP02 - WP03 | 350° |  100m |  1584m |
99 | WP03 - WP04 | 070° |   67m |  1651m |
100 | WP04 (J05) WP02 | 201° |  129m |  1779m |
101 | WP02 - WP03 | 350° |  100m |  1879m |
102 | WP03 - WP04 | 070° |   67m |  1946m |
103 | WP04 - WP06 | 089° |   71m |  2016m |
104 | WP06 - WP07 | 160° |   64m |  2081m |
105 | WP07 - PH09 | 226° |  159m |  2239m |
106 | PH09 - WP10 | 016° |  197m |  2437m |
107 | WP10 - WP11 | 164° |   92m |  2529m |
109 ## Modifier actions
110 A number of the WP types (JUMP, SET_POI, SET_HEAD, RTH) act as modifiers to the current location (i.e. the previous WP), as follows:
112 ### JUMP
113 JUMP facilitates adding loop to mission, the first parameter is the WP to jump to, and the second parameter is the number of times the JUMP is executed. A parameter2 value of `-1` means JUMP indefinitely (i.e. the pilot must eventually manually abort the mission and take control). For MultiWii, the jump target (parameter 1) must be prior to the jump WP, for inav, forward and backward jumps are permitted. In general, forward jumps are less useful and will usually need a backward jump to be useful.
115 inav validates JUMP WPs prior to arming; the following conditions will cause a "Navigation Unsafe" [arming blocker](https://github.com/iNavFlight/inav/wiki/%22Something%22-is-disabled----Reasons/_edit).
117 * First item can't be JUMP (can't calculate 1st WP distance, impossible for backward jumps)
118 * Can't jump to immediately adjacent WPs (pointless)
119 * Can't jump beyond WP list (undefined behaviour)
120 * Can only jump to geo-referenced WPs (WAYPOINT, POSHOLD_TIME, LAND) (otherwise, undefined behaviour)
122 In the following example of a forward jump, WP #5 (POSHOLD_TIME) is visited exactly once.
123 ![Jump Forward](images/forward-jump-mission.png)
126 <?xml version="1.0" encoding="utf-8"?>
127 <mission>
128   <missionitem no="1" action="WAYPOINT" lat="54.353504451478102" lon="-4.5171693008103739" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
129   <missionitem no="2" action="WAYPOINT" lat="54.353290963012334" lon="-4.5186271961455091" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
130   <missionitem no="3" action="WAYPOINT" lat="54.354462866400432" lon="-4.519133424449862" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
131   <missionitem no="4" action="JUMP" lat="0" lon="0" alt="0" parameter1="6" parameter2="2" parameter3="0"></missionitem>
132   <missionitem no="5" action="POSHOLD_TIME" lat="54.35511281066394" lon="-4.5180071708842604" alt="50" parameter1="30" parameter2="0" parameter3="0"></missionitem>
133   <missionitem no="6" action="WAYPOINT" lat="54.354418702382176" lon="-4.5170547858197763" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
134   <missionitem no="7" action="JUMP" lat="0" lon="0" alt="0" parameter1="1" parameter2="3" parameter3="0"></missionitem>
135   <missionitem no="8" action="WAYPOINT" lat="54.353913541022997" lon="-4.5182771029460111" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
136   <missionitem no="9" action="RTH" lat="0" lon="0" alt="0" parameter1="0" parameter2="0" parameter3="0"></missionitem>
137 </mission>
140 ### RTH
141 The craft returns to the home location.
143 ### SET POI (Multirotor only, multiwii, inav 2.6 and later)
145 The `SET_POI` defines a location for a point of interest (POI). The craft will fly the mission (until a `SET_HEAD`) with the nose pointing at the POI, which might be useful for aerial photography. Note that the craft does NOT fly to the POI.
147 In the following image:
149 * WP2 and WP11 are coincident.
150 * WP3 (yellow icon) defines the POI
151 * WP12 (`SET_HEAD -1`) cancels the POI
153 So the craft will fly normally from WP1 to WP2. The craft will then fly WP2 - WP11 with the "nose in" towards the POI (WP3).
155 After WP11, the craft flies normally, "nose first".
157 ![Set POI ](images/mission-set-poi.png)
159 [Youtube video tutorial on SET_POI and SET_HEAD](https://youtu.be/RO5N9tbzNg8)
161 ### SET_HEAD (Multirotor only, multiwii, inav 2.6 and later)
163 The `SET_HEAD` type sets the craft's heading (where it 'looks', not the direction of travel). This may be useful for useful for aerial photography. A value of `-1` causing the heading to be 'straight ahead', i.e. the direction of travel. Thus, `SET_POI` `-1` may used to cancel a previous valid `SET_HEAD` or `SET_POI`. A `SET_HEAD` remains in force until cancelled by `SET_HEAD` with `p1` of `-1`, or modified by a subsequent `SET_HEAD` or `SET_POI`.
165 In the following example (note that WP8 - WP9 is orientated 120°- 300°):
167 The craft flies normally (nose first) to WP1.
169 The craft flies WP1 - WP3 with the nose pointing 120° (i.e. at c. 90° relative to the track)
171 The craft flies WP3 - WP5 - WP6 with the nose pointing 300° (i.e. at c. 90° / 270° relative to the track).
173 The craft then files normally (nose first) WP6 - WP8 - WP9 (where it lands). The `SET_HEAD` with `P1 -1` at WP7 cancels the preceding `SET_HEAD`.
175 ![SET_HEAD image](images/mission-set-head.png)
177 ## Uploading
179 For safety, if no mission is defined, a single RTH action should be sent.
181 | Enum | P1 | P2 | P3 | Lat | Lon | Alt | Flag |
182 | ---- | ---- | ---- | ---- | ---- | ---- | ---- | ---- |
183 | RTH | 0 | 0 | 0 | 0 | 0 | 25m [1] | 0xa5 |
185 1. your choice, really.
187 In general, flag is 0, unless it's the last point in a mission, in which case it is set to 0xa5 (165) (or 0x48 (72) for FBH WP). When waypoints are uploaded, the values are also returned by the FC, thus enabling the application to verify that the mission has been uploaded correctly.
189 # Messages (Navigation related)
191 | MNEMONIC | Value | Direction (relative to FC) |
192 | -------- | ---- | ---- |
193 | MSP_NAV_STATUS | 121 | Out |
194 | MSP_NAV_CONFIG | 122 | Out |
195 | MSP_WP | 118  | Out |
196 | MSP_RADIO | 199 | Out |
197 | MSP_SET_NAV_CONFIG | 215 | In |
198 | MSP_SET_HEAD | 211 | In |
199 | MSP_SET_WP | 209 | In (& out) |
201 ## MSP_WP / MSP_SET_WP
203 Special waypoints are 0, 254, and 255. #0 returns the RTH (Home) position, #254 returns the current desired position (e.g. target waypoint), #255 returns the current position. WP #255 may also be used to set the vehicle's desired location (i.e. "follow me") when the following modes are asserted:
205 * NAV_POSHOLD
206 * GCS_NAV
208 | Name | Type | Usage |
209 | ---- | ---- | ----- |
210 | wp_no | uchar | way point number |
211 | action | uchar | action (wp type / action) |
212 | lat | int32 | decimal degrees latitude * 10,000,000 |
213 | lon | int32 | decimal degrees longitude * 10,000,000 |
214 | altitude | int32 | altitude (metre) * 100 |
215 | p1 | int16 | varies according to action |
216 | p2 | int16 | varies according to action |
217 | p3 | int16 | varies according to action |
218 | flag | uchar | 0xa5 = last, otherwise set to 0 (or 0x48 (72) for FBH WP, inav 3.1+)|
220 The values for the various parameters are given in the section “WayPoint / Action Attributes”
221 Note that altitude is measured from the "home" location, not absolute above mean sea level.
223 ## MSP_NAV_STATUS
225 The following data are returned by a MSP_NAV_STATUS message. The usage texts are those defined by Wingui; multiwii and inav support this message. Almost the same data is returned by the [inav LTM NFRAME](https://github.com/iNavFlight/inav/wiki/Lightweight-Telemetry-(LTM)#navigation-frame-n)
227 <table>
228 <thead>
229 <tr class="header">
230 <th>Name</th>
231 <th>Type</th>
232 <th>Usage</th>
233 </tr>
234 </thead>
235 <tbody>
236 <tr class="odd">
237 <td>gps_mode</td>
238 <td>uchar</td>
239 <td>None <br/>
240 PosHold <br/>
241 RTH <br/>
242 Mission</td>
243 </tr>
244 <tr class="even">
245 <td>nav_state</td>
246 <td>uchar</td>
247 <td>None <br/>
248 RTH Start <br/>
249 RTH Enroute <br/>
250 PosHold infinite<br/>
251 PosHold timed<br/>
252 WP Enroute <br/>
253 Process next <br/>
254 Jump <br/>
255 Start Land <br/>
256 Land in Progress <br/>
257 Landed <br/>
258 Settling before land <br/>
259 Start descent <br/>
260 Hover above home <br/>
261 Emergency Landing </td>
262 </tr>
263 <tr class="odd">
264 <td>action</td>
265 <td>uchar</td>
266 <td>(last wp, next wp?)</td>
267 </tr>
268 <tr class="even">
269 <td>wp_number</td>
270 <td>uchar</td>
271 <td>(last wp, next wp?)</td>
272 </tr>
273 <tr class="even">
274 <td>nav_error</td>
275 <td>uchar</td>
276 <td>Navigation system is working <br/>
277 Next waypoint distance is more than the safety limit, aborting mission <br/>
278 GPS reception is compromised - pausing mission, COPTER IS ADRIFT! <br/>
279 Error while reading next waypoint from memory, aborting mission. <br/>
280 Mission Finished. <br/>
281 Waiting for timed position hold. <br/>
282 Invalid Jump target detected, aborting mission. <br/>
283 Invalid Mission Step Action code detected, aborting mission. <br/>
284 Waiting to reach return to home altitude. <br/>
285 GPS fix lost, mission aborted - COPTER IS ADRIFT! <br/>
286 Copter is disarmed, navigation engine disabled. <br/>
287 Landing is in progress, check attitude if possible. </td>
288 </tr>
289 <tr class="odd">
290 <td>target_bearing</td>
291 <td>int16</td>
292 <td>(presumably to the next WP?)</td>
293 </tr>
294 </tbody>
295 </table>
297 ## MSP_NAV_CONFIG (MW)
299 The following data are returned from a MSP_NAV_CONFIG message. Values are from multiwii config.h. Values may also be set by MSP_SET_NAV_CONFIG.
301 <table>
302 <thead>
303 <tr class="header">
304 <th>Name</th>
305 <th>Type</th>
306 <th>Usage</th>
307 </tr>
308 </thead>
309 <tbody>
310 <tr class="odd">
311 <td>flags1</td>
312 <td>uchar</td>
313 <td>
314 Bitmap of settings from MW config.h <br/>
315 b0 : GPS filtering <br/>
316 b1 : GPS Lead <br/>
317 b2 : Reset Home <br/>
318 b3 : Heading control <br/>
319 b4 : Tail first <br/>
320 b5 : RTH Head <br/>
321 b6 : Slow Nav <br/>
322 b7 : RTH Alt </td>
323 </tr>
324 <tr class="even">
325 <td>flags2</td>
326 <td>uchar</td>
327 <td>
328 Bitmap of settings from MW config.h <br/>
329 b0 : Disable sticks <br/>
330 b1 : Baro takeover</td>
331 </tr>
332 <tr class="odd">
333 <td>wp_radius</td>
334 <td>uint16</td>
335 <td>radius around which waypoint is reached (cm)</td>
336 <tr class="even">
337 <td>safe_wp_distance</td>
338 <td>uint16</td>
339 <td>Maximum permitted first leg of mission (m, assumed?)</td>
340 </tr>
341 <tr class="odd">
342 <td>nav_max_altitude</td>
343 <td>uint16</td>
344 <td>Maximum altitude for NAV (m)</td>
345 </tr>
346 <tr class="even">
347 <td>nav_speed_max</td>
348 <td>uint16</td>
349 <td>maximum speed for NAV (cm/sec)</td>
350 </tr>
351 <tr class="odd">
352 <td>nav_speed_min</td>
353 <td>uint16</td>
354 <td>minimum speed for NAV (cm/s)</td>
355 </tr>
356 <tr class="even">
357 <td>crosstrack_gain</td>
358 <td>uchar</td>
359 <td>MW config.h value*100</td>
360 </tr>
361 <tr class="odd">
362 <td>nav_bank_max</td>
363 <td>uint16</td>
364 <td>maximum bank ??? for NAV, MW config.h value*100</td>
365 </tr>
366 <tr class="even">
367 <td>rth_altitude</td>
368 <td>uint16</td>
369 <td>RTH altitude (m)</td>
370 </tr>
371 <tr class="odd">
372 <td>land_speed</td>
373 <td>uchar</td>
374 <td>Governs the descent speed during landing. 100 ~= 50 cm/sec unknown units</td>
375 </tr>
376 <tr class="even">
377 <td>fence</td>
378 <td>uint16</td>
379 <td>Distance beyond which forces RTH (m)</td>
380 </tr>
381 <tr class="odd">
382 <td>max_wp_number</td>
383 <td>uchar</td>
384 <td>maximum number of waypoints possible (read only)</td>
385 </tr>
386 </tbody>
387 </table>
389 ## MSP_RADIO
391 If you have a 3DR radio with the MW/MSP specific firmware, the follow data are sent from the radio, unsolicited.
393 | Name | Type | Usage |
394 | ---- | ---- | ----- |
395 | rxerrors | uint16 | Number of RX errors |
396 | fixed_errors | uint16 | Number of fixed errors, if error correction is set |
397 | localrssi | uchar | Local RSSI |
398 | remrssi | uchar | Remote RSSI |
399 | txbuf  | uchar | Size of TX buffer |
400 | noise | uchar | Local noise |
401 | remnoise | uchar | Remote noise |
403 ## FC Capabilities (MW only)
405 Note that 32bit flight controllers (baseflight, cleanflight) use capability == 16 for a different purpose
406 (CAP_CHANNEL_FORWARDING). It is advised to use other messages for checking for capabilities on non-MW platforms.
408 | Capability | Value |
409 | ---- | ---- |
410 | BIND | 1 |
411 | DYNBAL | 4 |
412 | FLAP | 8 |
413 | NAV | 16 |
415 # Implementations
417 The MSP NAV message set is implemented by [mwptools](https://github.com/stronnag/mwptools) (Linux, Windows, FreeBSD), ezgui / mission planner for iNav (Android), WinGUI (MS Windows) and the [inav-configurator](https://github.com/iNavFlight/inav-configurator).
419 # XML Mission Files
421 [mwptools](https://github.com/stronnag/mwptools), ezgui / mp4i, [inav-configurator](https://github.com/iNavFlight/inav-configurator) (and WinGUI) share a common, interoperable, XML mission file format. A [reverse engineered definition (XSD)](https://github.com/stronnag/mwptools/blob/master/src/samples/mw-mission.xsd) can be found in the [mwp](https://github.com/stronnag/mwptools) samples directory.