Skip to main content
Version: 6.1.1

MSP Navigation Messages

MSP NAV Protocol and Types

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.

Note that all binary values are little endian (MSP standard).

Implementation and versions

This document should match the INAV 1.2 (and later) and Multiwii 2.5 flight controller firmware.

Prior to INAV 3.0, the 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 (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.

WayPoint and Action Attributes

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).

ValueEnumP1P2P3LatLonAltINAV
1WAYPOINTSpeed (cm/s) [1] (exception [6])Altitude Mode [7]
2POSHOLD_UNLIM[5]
3POSHOLD_TIMEWait time (seconds)(speed (cm/s)[1])Altitude Mode [7]✔ 2.5 and later
4RTH [4]Land if non-zero✔ [2]
5SET_POI [3]✔ 2.6 and later
6JUMPTarget WP#No. of repeats (-1 = forever)✔ 2.5 and later
7SET_HEAD [3]Heading (degrees)✔ 2.6 and later
8LANDSpeed (cm/s) [1]Elevation Adjustment (m) [8]Altitude Mode [7]✔ 2.5 and later
  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).
  2. Not used by inav
  3. Once SET_HEAD or SET_POI is invoked, it remains active until cleared by SET_HEAD with a P1 value of -1.
  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.
  5. If the final entry in a mission is a WAYPOINT, the inav treats it as POSHOLD_UNLIM.
  6. For inav's "follow-me" mode (WP#255, POSHOLD engaged), P1 may be used to send an orientation heading (0-359 degrees).
  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.
  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.

Geospatial Units

FieldXML Mission FileMSP_WP binary message
Latitude, LongitudeDecimal degrees, WGS84Integer, WGS84 Degrees * 1E7
AltitudeInteger MetresCentimetres

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.

FlyBy Home Waypoints

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

  • The latitude and longitude is zero; or
  • The flag field is set to 0x48 (72d, 'H')

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.

Annotated Example

The following example, using the MW XML (inav configurator, mwp, ez-gui) format, illustrates the WAYPOINT, JUMP, POSHOLD_TIME and LAND types: Complex Mission

<?xml version="1.0" encoding="utf-8"?>
<mission>
<missionitem no="1" action="WAYPOINT" lat="54.353319318038153" lon="-4.5179273723848077" alt="35" parameter1="0" parameter2="0" parameter3="0"></missionitem>
<missionitem no="2" action="WAYPOINT" lat="54.353572350395972" lon="-4.5193913118652516" alt="35" parameter1="0" parameter2="0" parameter3="0"></missionitem>
<missionitem no="3" action="WAYPOINT" lat="54.354454163955907" lon="-4.5196617811150759" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
<missionitem no="4" action="WAYPOINT" lat="54.354657830207479" lon="-4.5186895986330455" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
<missionitem no="5" action="JUMP" lat="0" lon="0" alt="0" parameter1="2" parameter2="2" parameter3="0"></missionitem>
<missionitem no="6" action="WAYPOINT" lat="54.354668848061756" lon="-4.5176009696657218" alt="35" parameter1="0" parameter2="0" parameter3="0"></missionitem>
<missionitem no="7" action="WAYPOINT" lat="54.354122567317191" lon="-4.5172673708680122" alt="35" parameter1="0" parameter2="0" parameter3="0"></missionitem>
<missionitem no="8" action="JUMP" lat="0" lon="0" alt="0" parameter1="1" parameter2="1" parameter3="0"></missionitem>
<missionitem no="9" action="POSHOLD_TIME" lat="54.353138333126651" lon="-4.5190405596657968" alt="35" parameter1="45" parameter2="0" parameter3="0"></missionitem>
<missionitem no="10" action="WAYPOINT" lat="54.354847022143616" lon="-4.518210497615712" alt="35" parameter1="0" parameter2="0" parameter3="0"></missionitem>
<missionitem no="11" action="LAND" lat="54.354052100964488" lon="-4.5178091504726012" alt="60" parameter1="0" parameter2="0" parameter3="0"></missionitem>
</mission>

Mission points 5 and 8 are JUMP; they have no location as they affect the current location (the previous WP) and cause an action.

  • 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.
  • 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.
  • The second JUMP (8) will cause the first jump (5) to be re-executed.

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.

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.

There is a video animation of the flight in a short youtube video and a more detailed youtube video tutorial. The mission is executed as:

WP / next wpCourseDistTotal
WP01 - WP02287°99m99m
WP02 - WP03350°100m198m
WP03 - WP04070°67m265m
WP04 (J05) WP02201°129m394m
WP02 - WP03350°100m494m
WP03 - WP04070°67m561m
WP04 (J05) WP02201°129m690m
WP02 - WP03350°100m789m
WP03 - WP04070°67m856m
WP04 - WP06089°71m927m
WP06 - WP07160°64m991m
WP07 (J08) WP01206°99m1090m
WP01 - WP02287°99m1189m
WP02 - WP03350°100m1288m
WP03 - WP04070°67m1355m
WP04 (J05) WP02201°129m1484m
WP02 - WP03350°100m1584m
WP03 - WP04070°67m1651m
WP04 (J05) WP02201°129m1779m
WP02 - WP03350°100m1879m
WP03 - WP04070°67m1946m
WP04 - WP06089°71m2016m
WP06 - WP07160°64m2081m
WP07 - PH09226°159m2239m
PH09 - WP10016°197m2437m
WP10 - WP11164°92m2529m

Modifier actions

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:

JUMP

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.

INAV validates JUMP WPs prior to arming; the following conditions will cause a "Navigation Unsafe" arming blocker.

  • First item can't be JUMP (can't calculate 1st WP distance, impossible for backward jumps)
  • Can't jump to immediately adjacent WPs (pointless)
  • Can't jump beyond WP list (undefined behaviour)
  • Can only jump to geo-referenced WPs (WAYPOINT, POSHOLD_TIME, LAND) (otherwise, undefined behaviour)

In the following example of a forward jump, WP #5 (POSHOLD_TIME) is visited exactly once. Jump Forward

<?xml version="1.0" encoding="utf-8"?>
<mission>
<missionitem no="1" action="WAYPOINT" lat="54.353504451478102" lon="-4.5171693008103739" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
<missionitem no="2" action="WAYPOINT" lat="54.353290963012334" lon="-4.5186271961455091" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
<missionitem no="3" action="WAYPOINT" lat="54.354462866400432" lon="-4.519133424449862" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
<missionitem no="4" action="JUMP" lat="0" lon="0" alt="0" parameter1="6" parameter2="2" parameter3="0"></missionitem>
<missionitem no="5" action="POSHOLD_TIME" lat="54.35511281066394" lon="-4.5180071708842604" alt="50" parameter1="30" parameter2="0" parameter3="0"></missionitem>
<missionitem no="6" action="WAYPOINT" lat="54.354418702382176" lon="-4.5170547858197763" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
<missionitem no="7" action="JUMP" lat="0" lon="0" alt="0" parameter1="1" parameter2="3" parameter3="0"></missionitem>
<missionitem no="8" action="WAYPOINT" lat="54.353913541022997" lon="-4.5182771029460111" alt="50" parameter1="0" parameter2="0" parameter3="0"></missionitem>
<missionitem no="9" action="RTH" lat="0" lon="0" alt="0" parameter1="0" parameter2="0" parameter3="0"></missionitem>
</mission>

RTH

The craft returns to the home location.

SET POI (Multirotor only, multiwii, inav 2.6 and later)

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.

In the following image:

  • WP2 and WP11 are coincident.
  • WP3 (yellow icon) defines the POI
  • WP12 (SET_HEAD -1) cancels the POI

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).

After WP11, the craft flies normally, "nose first".

Set POI

Youtube video tutorial on SET_POI and SET_HEAD

SET_HEAD (Multirotor only, multiwii, inav 2.6 and later)

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.

In the following example (note that WP8 - WP9 is orientated 120°- 300°):

The craft flies normally (nose first) to WP1.

The craft flies WP1 - WP3 with the nose pointing 120° (i.e. at c. 90° relative to the track)

The craft flies WP3 - WP5 - WP6 with the nose pointing 300° (i.e. at c. 90° / 270° relative to the track).

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.

SET_HEAD image

Uploading

For safety, if no mission is defined, a single RTH action should be sent.

EnumP1P2P3LatLonAltFlag
RTH0000025m [1]0xa5
  1. your choice, really.

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.

MNEMONICValueDirection (relative to FC)
MSP_NAV_STATUS121Out
MSP_NAV_CONFIG122Out
MSP_WP118Out
MSP_RADIO199Out
MSP_SET_NAV_CONFIG215In
MSP_SET_HEAD211In
MSP_SET_WP209In (& out)

MSP_WP / MSP_SET_WP

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:

  • NAV_POSHOLD
  • GCS_NAV
NameTypeUsage
wp_noucharway point number
actionucharaction (wp type / action)
latint32decimal degrees latitude * 10,000,000
lonint32decimal degrees longitude * 10,000,000
altitudeint32altitude (metre) * 100
p1int16varies according to action
p2int16varies according to action
p3int16varies according to action
flaguchar0xa5 = last, otherwise set to 0 (or 0x48 (72) for FBH WP, inav 3.1+)

The values for the various parameters are given in the section “WayPoint / Action Attributes” 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).

MSP_NAV_STATUS

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

NameTypeUsage
gps_modeucharNone
PosHold
RTH
Mission
nav_stateucharNone
RTH Start
RTH Enroute
PosHold infinite
PosHold timed
WP Enroute
Process next
Jump
Start Land
Land in Progress
Landed
Settling before land
Start descent
Hover above home
Emergency Landing
actionuchar(last wp, next wp?)
wp_numberuchar(last wp, next wp?)
nav_errorucharNavigation system is working
Next waypoint distance is more than the safety limit, aborting mission
GPS reception is compromised - pausing mission, COPTER IS ADRIFT!
Error while reading next waypoint from memory, aborting mission.
Mission Finished.
Waiting for timed position hold.
Invalid Jump target detected, aborting mission.
Invalid Mission Step Action code detected, aborting mission.
Waiting to reach return to home altitude.
GPS fix lost, mission aborted - COPTER IS ADRIFT!
Copter is disarmed, navigation engine disabled.
Landing is in progress, check attitude if possible.
target_bearingint16(presumably to the next WP?)

MSP_NAV_CONFIG (MW)

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.

NameTypeUsage
flags1uchar

Bitmap of settings from MW config.h
b0 : GPS filtering
b1 : GPS Lead
b2 : Reset Home
b3 : Heading control
b4 : Tail first
b5 : RTH Head
b6 : Slow Nav
b7 : RTH Alt

flags2uchar

Bitmap of settings from MW config.h
b0 : Disable sticks
b1 : Baro takeover

wp_radiusuint16radius around which waypoint is reached (cm)
safe_wp_distanceuint16Maximum permitted first leg of mission (m, assumed?)
nav_max_altitudeuint16Maximum altitude for NAV (m)
nav_speed_maxuint16maximum speed for NAV (cm/sec)
nav_speed_minuint16minimum speed for NAV (cm/s)
crosstrack_gainucharMW config.h value*100
nav_bank_maxuint16maximum bank ??? for NAV, MW config.h value*100
rth_altitudeuint16RTH altitude (m)
land_speeducharGoverns the descent speed during landing. 100 ~= 50 cm/sec unknown units
fenceuint16Distance beyond which forces RTH (m)
max_wp_numberucharmaximum number of waypoints possible (read only)

MSP_RADIO

If you have a 3DR radio with the MW/MSP specific firmware, the follow data are sent from the radio, unsolicited.

NameTypeUsage
rxerrorsuint16Number of RX errors
fixed_errorsuint16Number of fixed errors, if error correction is set
localrssiucharLocal RSSI
remrssiucharRemote RSSI
txbufucharSize of TX buffer
noiseucharLocal noise
remnoiseucharRemote noise

FC Capabilities (MW only)

Note that 32bit flight controllers (baseflight, cleanflight) use capability == 16 for a different purpose (CAP_CHANNEL_FORWARDING). It is advised to use other messages for checking for capabilities on non-MW platforms.

CapabilityValue
BIND1
DYNBAL4
FLAP8
NAV16

Implementations

The MSP NAV message set is implemented by mwptools (Linux, Windows, FreeBSD), ezgui / mission planner for iNav (Android), WinGUI (MS Windows) and the inav-configurator.

XML Mission Files

inav-configurator, mwptools, ezgui / mp4i (and WinGUI) share a common, interoperable, XML mission file format. A XSD can be found in the inav developer documenation.