improve special wp description
[inav.wiki.git] / MSP-Navigation-Messages.md
blobb96100100562cb094a7408508f68c39767b70124
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.
11 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 supports all WP types. In addition to the inav configurator, 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.
13 # WayPoint and Action Attributes
15 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).
17 | Value | Enum | P1 | P2 | P3 | Lat | Lon | Alt | INAV |
18 | ---- | ---- | ---- | ---- | ---- | ---- | ---- | ---- | ---- |
19 | 1 | WAYPOINT      | Speed (cm/s) [1] (exception [6]) | | Altitude Mode & Actions [7] | ✔ | ✔ | ✔ | ✔ |
20 | 2 | POSHOLD_UNLIM |          | | | ✔ | ✔ | ✔ | [5] |
21 | 3 | POSHOLD_TIME  | Wait time (seconds) | (speed (cm/s)[1]) | Altitude Mode & Actions [7] | ✔ | ✔ | ✔ | ✔ 2.5 and later |
22 | 4 | RTH [4]       | Land if non-zero | | |    |    | ✔ [2] | ✔ |
23 | 5 | SET_POI [3]   |          | | | ✔ | ✔ | | ✔ 2.6 and later |
24 | 6 | JUMP          | Target WP#      | No. of repeats (-1 = forever) | | | | | ✔ 2.5 and later |
25 | 7 | SET_HEAD [3]  | Heading  (degrees) | | | | | | ✔ 2.6 and later |
26 | 8 | LAND | Speed (cm/s) [1] | Elevation Adjustment (m) [8] | Altitude Mode & Actions [7] | ✔ | ✔ | ✔ | ✔ 2.5 and later |
28 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).
29 2. Not used by INAV
30 3. Once SET_HEAD or SET_POI is invoked, it remains active until cleared by SET_HEAD with a P1 value of -1.
31 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.
32 5. If the final entry in a mission is a WAYPOINT, the INAV treats it as POSHOLD_UNLIM.
33 6. For INAV's "follow-me" mode (WP#255, POSHOLD engaged), P1 may be used to send an orientation heading (0-359 degrees).
34 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. INAV 6.0 and later additionally define user "Actions" which may be invoked using the logic programming framework.
35 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.
37 ## P3 bitfield usage
39 Since INAV 6.0, the usage of the P3 parameter is:
41 | Bit | Usage |
42 | ---- | ---- |
43 | 0 | Relative (not set) or absolute (AMSL) (set) altitude reference |
44 | 1 | User Action 1 |
45 | 2 | User Action 2 |
46 | 3 | User Action 3 |
47 | 4 | User Action 4 |
48 | 5-15 | Reserved |
50 ## Geospatial Units
52 | Field | XML Mission File | MSP_WP binary message |
53 | ----- | ---------------- | --------------------- |
54 | Latitude, Longitude | Decimal degrees, WGS84 | Integer, WGS84 Degrees * 1E7 |
55 | Altitude | Integer Metres | Centimetres |
57 Note that INAV uses the GPS' "above mean sea level" (not "above WGS84 ellipsoid") elevation for navigation. Be aware of this distinction when using absolute  rather than relative (to home) mission altitudes.
59 ## FlyBy Home Waypoints
61 From INAV 4.0, "FlyBy Home" (FBH) waypoints are supported for WAYPOINT, POSHOLD_TIME and LAND. These WPs are designated by either (or both) of
62 * The latitude and longitude is zero; or
63 * The `flag` field is set to 0x48 (72d, 'H')
65 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.
67 ## Annotated Example
68 The following example, using the [MW XML](#xml-mission-files) (INAV configurator, mwp, ez-gui) format, illustrates the WAYPOINT, JUMP, POSHOLD_TIME and LAND types:
69 ![Complex Mission](images/eg_complex_mission.png)
70 ```
71 <?xml version="1.0" encoding="utf-8"?>
72 <mission>
73   <missionitem no="1" action="WAYPOINT" lat="54.353319318038153" lon="-4.5179273723848077" alt="35" parameter1="0" parameter2="0" parameter3="0"></missionitem>
74   <missionitem no="2" action="WAYPOINT" lat="54.353572350395972" lon="-4.5193913118652516" alt="35" parameter1="0" parameter2="0" parameter3="0"></missionitem>
75   <missionitem no="3" action="WAYPOINT" lat="54.354454163955907" lon="-4.5196617811150759" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
76   <missionitem no="4" action="WAYPOINT" lat="54.354657830207479" lon="-4.5186895986330455" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
77   <missionitem no="5" action="JUMP" lat="0" lon="0" alt="0" parameter1="2" parameter2="2" parameter3="0"></missionitem>
78   <missionitem no="6" action="WAYPOINT" lat="54.354668848061756" lon="-4.5176009696657218" alt="35" parameter1="0" parameter2="0" parameter3="0"></missionitem>
79   <missionitem no="7" action="WAYPOINT" lat="54.354122567317191" lon="-4.5172673708680122" alt="35" parameter1="0" parameter2="0" parameter3="0"></missionitem>
80   <missionitem no="8" action="JUMP" lat="0" lon="0" alt="0" parameter1="1" parameter2="1" parameter3="0"></missionitem>
81   <missionitem no="9" action="POSHOLD_TIME" lat="54.353138333126651" lon="-4.5190405596657968" alt="35" parameter1="45" parameter2="0" parameter3="0"></missionitem>
82   <missionitem no="10" action="WAYPOINT" lat="54.354847022143616" lon="-4.518210497615712" alt="35" parameter1="0" parameter2="0" parameter3="0"></missionitem>
83   <missionitem no="11" action="LAND" lat="54.354052100964488" lon="-4.5178091504726012" alt="60" parameter1="0" parameter2="0" parameter3="0"></missionitem>
84 </mission>
85 ```
86 Mission points 5 and 8 are JUMP; they have no location as they affect the current location (the previous WP) and cause an action.
87 * 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.
88 * 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.
89 * The second JUMP (8) will cause the first jump (5) to be re-executed.
91 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`.
93 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.
95 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:
97 | WP / next wp | Course |  Dist |  Total |
98 | ------------ | ------ | ----- | ------ |
99 | WP01 - WP02 | 287° |   99m |    99m |
100 | WP02 - WP03 | 350° |  100m |   198m |
101 | WP03 - WP04 | 070° |   67m |   265m |
102 | WP04 (J05) WP02 | 201° |  129m |   394m |
103 | WP02 - WP03 | 350° |  100m |   494m |
104 | WP03 - WP04 | 070° |   67m |   561m |
105 | WP04 (J05) WP02 | 201° |  129m |   690m |
106 | WP02 - WP03 | 350° |  100m |   789m |
107 | WP03 - WP04 | 070° |   67m |   856m |
108 | WP04 - WP06 | 089° |   71m |   927m |
109 | WP06 - WP07 | 160° |   64m |   991m |
110 | WP07 (J08) WP01 | 206° |   99m |  1090m |
111 | WP01 - WP02 | 287° |   99m |  1189m |
112 | WP02 - WP03 | 350° |  100m |  1288m |
113 | WP03 - WP04 | 070° |   67m |  1355m |
114 | WP04 (J05) WP02 | 201° |  129m |  1484m |
115 | WP02 - WP03 | 350° |  100m |  1584m |
116 | WP03 - WP04 | 070° |   67m |  1651m |
117 | WP04 (J05) WP02 | 201° |  129m |  1779m |
118 | WP02 - WP03 | 350° |  100m |  1879m |
119 | WP03 - WP04 | 070° |   67m |  1946m |
120 | WP04 - WP06 | 089° |   71m |  2016m |
121 | WP06 - WP07 | 160° |   64m |  2081m |
122 | WP07 - PH09 | 226° |  159m |  2239m |
123 | PH09 - WP10 | 016° |  197m |  2437m |
124 | WP10 - WP11 | 164° |   92m |  2529m |
126 ## Modifier actions
127 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:
129 ### JUMP
130 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.
132 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).
134 * First item can't be JUMP (can't calculate 1st WP distance, impossible for backward jumps)
135 * Can't jump to immediately adjacent WPs (pointless)
136 * Can't jump beyond WP list (undefined behaviour)
137 * Can only jump to geo-referenced WPs (WAYPOINT, POSHOLD_TIME, LAND) (otherwise, undefined behaviour)
139 In the following example of a forward jump, WP #5 (POSHOLD_TIME) is visited exactly once.
140 ![Jump Forward](images/forward-jump-mission.png)
143 <?xml version="1.0" encoding="utf-8"?>
144 <mission>
145   <missionitem no="1" action="WAYPOINT" lat="54.353504451478102" lon="-4.5171693008103739" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
146   <missionitem no="2" action="WAYPOINT" lat="54.353290963012334" lon="-4.5186271961455091" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
147   <missionitem no="3" action="WAYPOINT" lat="54.354462866400432" lon="-4.519133424449862" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
148   <missionitem no="4" action="JUMP" lat="0" lon="0" alt="0" parameter1="6" parameter2="2" parameter3="0"></missionitem>
149   <missionitem no="5" action="POSHOLD_TIME" lat="54.35511281066394" lon="-4.5180071708842604" alt="50" parameter1="30" parameter2="0" parameter3="0"></missionitem>
150   <missionitem no="6" action="WAYPOINT" lat="54.354418702382176" lon="-4.5170547858197763" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
151   <missionitem no="7" action="JUMP" lat="0" lon="0" alt="0" parameter1="1" parameter2="3" parameter3="0"></missionitem>
152   <missionitem no="8" action="WAYPOINT" lat="54.353913541022997" lon="-4.5182771029460111" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
153   <missionitem no="9" action="RTH" lat="0" lon="0" alt="0" parameter1="0" parameter2="0" parameter3="0"></missionitem>
154 </mission>
157 ### RTH
158 The craft returns to the home location.
160 ### SET POI (Multirotor only, Multiwii, INAV 2.6 and later)
162 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.
164 In the following image:
166 * WP2 and WP11 are coincident.
167 * WP3 (yellow icon) defines the POI
168 * WP12 (`SET_HEAD -1`) cancels the POI
170 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).
172 After WP11, the craft flies normally, "nose first".
174 ![Set POI ](images/mission-set-poi.png)
176 [Youtube video tutorial on SET_POI and SET_HEAD](https://youtu.be/RO5N9tbzNg8)
178 ### SET_HEAD (Multirotor only, Multiwii, INAV 2.6 and later)
180 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_HEAD` `-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`.
182 In the following example (note that WP8 - WP9 is orientated 120°- 300°):
184 The craft flies normally (nose first) to WP1.
186 The craft flies WP1 - WP3 with the nose pointing 120° (i.e. at c. 90° relative to the track)
188 The craft flies WP3 - WP5 - WP6 with the nose pointing 300° (i.e. at c. 90° / 270° relative to the track).
190 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`.
192 ![SET_HEAD image](images/mission-set-head.png)
194 ## Uploading
196 For safety, if no mission is defined, a single RTH action should be sent.
198 | Enum | P1 | P2 | P3 | Lat | Lon | Alt | Flag |
199 | ---- | ---- | ---- | ---- | ---- | ---- | ---- | ---- |
200 | RTH | 0 | 0 | 0 | 0 | 0 | 25m [1] | 0xa5 |
202 1. your choice, really.
204 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 same data can also be requested from he FC, thus enabling the application to verify that the mission has been uploaded correctly.
206 # Messages (Navigation related)
208 | MNEMONIC | Value | Direction (relative to FC) |
209 | -------- | ---- | ---- |
210 | MSP_NAV_STATUS | 121 | Out |
211 | MSP_NAV_CONFIG | 122 | Out |
212 | MSP_WP | 118  | Out |
213 | MSP_RADIO | 199 | Out |
214 | MSP_SET_NAV_CONFIG | 215 | In |
215 | MSP_SET_HEAD | 211 | In |
216 | MSP_SET_WP | 209 | In (& out) |
218 ## MSP_WP / MSP_SET_WP
220 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.
222 | Name | Type | Usage |
223 | ---- | ---- | ----- |
224 | wp_no | uchar | way point number |
225 | action | uchar | action (wp type / action) |
226 | lat | int32 | decimal degrees latitude * 10,000,000 |
227 | lon | int32 | decimal degrees longitude * 10,000,000 |
228 | altitude | int32 | altitude (metre) * 100 |
229 | p1 | int16 | varies according to action |
230 | p2 | int16 | varies according to action |
231 | p3 | int16 | varies according to action |
232 | flag | uchar | 0xa5 = last, otherwise set to 0 (or 0x48 (72) for FBH WP, INAV 3.1+)|
234 The values for the various parameters are given in the section “WayPoint / Action Attributes”
235 Note that altitude is measured from the "home" location, not absolute above mean sea level, unless the absolute altitude flag is set for a WP (INAV 3.0 and later).
237 ## Updating special waypoints
239 When the craft has a valid position, is armed and the mode `GCS NAV` is asserted, two of the special waypoints may be updated using `MSP_SET_WP`:
241 WP#255 may be updated to set the vehicle's desired location (i.e. "Follow Me"); this also requires that `NAV POSHOLD` mode is asserted. If the altitude is 0, then the vehicle altitude is unchanged, otherwise it is set as desired relative altitude. If 'P1' is in the range 1-359, the heading is also updated, so "nose first follow me" is possible for a multi-rotor.
243 WP#0 may be updated to update the home position.
245 ## MSP_NAV_STATUS
247 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)
249 <table>
250 <thead>
251 <tr class="header">
252 <th>Name</th>
253 <th>Type</th>
254 <th>Usage</th>
255 </tr>
256 </thead>
257 <tbody>
258 <tr class="odd">
259 <td>gps_mode</td>
260 <td>uchar</td>
261 <td>None <br/>
262 PosHold <br/>
263 RTH <br/>
264 Mission</td>
265 </tr>
266 <tr class="even">
267 <td>nav_state</td>
268 <td>uchar</td>
269 <td>None <br/>
270 RTH Start <br/>
271 RTH Enroute <br/>
272 PosHold infinite<br/>
273 PosHold timed<br/>
274 WP Enroute <br/>
275 Process next <br/>
276 Jump <br/>
277 Start Land <br/>
278 Land in Progress <br/>
279 Landed <br/>
280 Settling before land <br/>
281 Start descent <br/>
282 Hover above home <br/>
283 Emergency Landing </td>
284 </tr>
285 <tr class="odd">
286 <td>action</td>
287 <td>uchar</td>
288 <td>(last wp, next wp?)</td>
289 </tr>
290 <tr class="even">
291 <td>wp_number</td>
292 <td>uchar</td>
293 <td>(last wp, next wp?)</td>
294 </tr>
295 <tr class="even">
296 <td>nav_error</td>
297 <td>uchar</td>
298 <td>Navigation system is working <br/>
299 Next waypoint distance is more than the safety limit, aborting mission <br/>
300 GPS reception is compromised - pausing mission, COPTER IS ADRIFT! <br/>
301 Error while reading next waypoint from memory, aborting mission. <br/>
302 Mission Finished. <br/>
303 Waiting for timed position hold. <br/>
304 Invalid Jump target detected, aborting mission. <br/>
305 Invalid Mission Step Action code detected, aborting mission. <br/>
306 Waiting to reach return to home altitude. <br/>
307 GPS fix lost, mission aborted - COPTER IS ADRIFT! <br/>
308 Copter is disarmed, navigation engine disabled. <br/>
309 Landing is in progress, check attitude if possible. </td>
310 </tr>
311 <tr class="odd">
312 <td>target_bearing</td>
313 <td>int16</td>
314 <td>(presumably to the next WP?)</td>
315 </tr>
316 </tbody>
317 </table>
319 ## MSP_NAV_CONFIG (MW)
321 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.
323 <table>
324 <thead>
325 <tr class="header">
326 <th>Name</th>
327 <th>Type</th>
328 <th>Usage</th>
329 </tr>
330 </thead>
331 <tbody>
332 <tr class="odd">
333 <td>flags1</td>
334 <td>uchar</td>
335 <td>
336 Bitmap of settings from MW config.h <br/>
337 b0 : GPS filtering <br/>
338 b1 : GPS Lead <br/>
339 b2 : Reset Home <br/>
340 b3 : Heading control <br/>
341 b4 : Tail first <br/>
342 b5 : RTH Head <br/>
343 b6 : Slow Nav <br/>
344 b7 : RTH Alt </td>
345 </tr>
346 <tr class="even">
347 <td>flags2</td>
348 <td>uchar</td>
349 <td>
350 Bitmap of settings from MW config.h <br/>
351 b0 : Disable sticks <br/>
352 b1 : Baro takeover</td>
353 </tr>
354 <tr class="odd">
355 <td>wp_radius</td>
356 <td>uint16</td>
357 <td>radius around which waypoint is reached (cm)</td>
358 <tr class="even">
359 <td>safe_wp_distance</td>
360 <td>uint16</td>
361 <td>Maximum permitted first leg of mission (m, assumed?)</td>
362 </tr>
363 <tr class="odd">
364 <td>nav_max_altitude</td>
365 <td>uint16</td>
366 <td>Maximum altitude for NAV (m)</td>
367 </tr>
368 <tr class="even">
369 <td>nav_speed_max</td>
370 <td>uint16</td>
371 <td>maximum speed for NAV (cm/sec)</td>
372 </tr>
373 <tr class="odd">
374 <td>nav_speed_min</td>
375 <td>uint16</td>
376 <td>minimum speed for NAV (cm/s)</td>
377 </tr>
378 <tr class="even">
379 <td>crosstrack_gain</td>
380 <td>uchar</td>
381 <td>MW config.h value*100</td>
382 </tr>
383 <tr class="odd">
384 <td>nav_bank_max</td>
385 <td>uint16</td>
386 <td>maximum bank ??? for NAV, MW config.h value*100</td>
387 </tr>
388 <tr class="even">
389 <td>rth_altitude</td>
390 <td>uint16</td>
391 <td>RTH altitude (m)</td>
392 </tr>
393 <tr class="odd">
394 <td>land_speed</td>
395 <td>uchar</td>
396 <td>Governs the descent speed during landing. 100 ~= 50 cm/sec unknown units</td>
397 </tr>
398 <tr class="even">
399 <td>fence</td>
400 <td>uint16</td>
401 <td>Distance beyond which forces RTH (m)</td>
402 </tr>
403 <tr class="odd">
404 <td>max_wp_number</td>
405 <td>uchar</td>
406 <td>maximum number of waypoints possible (read only)</td>
407 </tr>
408 </tbody>
409 </table>
411 ## MSP_RADIO
413 If you have a 3DR radio with the MW/MSP specific firmware, the follow data are sent from the radio, unsolicited.
415 | Name | Type | Usage |
416 | ---- | ---- | ----- |
417 | rxerrors | uint16 | Number of RX errors |
418 | fixed_errors | uint16 | Number of fixed errors, if error correction is set |
419 | localrssi | uchar | Local RSSI |
420 | remrssi | uchar | Remote RSSI |
421 | txbuf  | uchar | Size of TX buffer |
422 | noise | uchar | Local noise |
423 | remnoise | uchar | Remote noise |
425 ## FC Capabilities (MW only)
427 Note that 32bit flight controllers (baseflight, cleanflight) use capability == 16 for a different purpose
428 (CAP_CHANNEL_FORWARDING). It is advised to use other messages for checking for capabilities on non-MW platforms.
430 | Capability | Value |
431 | ---- | ---- |
432 | BIND | 1 |
433 | DYNBAL | 4 |
434 | FLAP | 8 |
435 | NAV | 16 |
437 # Implementations
439 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).
441 # XML Mission Files
443 [inav-configurator](https://github.com/iNavFlight/inav-configurator), [mwptools](https://github.com/stronnag/mwptools), ezgui / mp4i (and WinGUI) share a common, interoperable, XML mission file format. A XSD can be found in the [inav developer documenation](
444 https://github.com/iNavFlight/inav/tree/master/docs/development/wp_mission_schema).