Skip to content

Mission Mode (Fixed-Wing)

Mission mode causes the vehicle to execute a predefined autonomous mission (flight plan) that has been uploaded to the flight controller. The mission is typically created and uploaded with a Ground Control Station (GCS) application like QGroundControl (QGC).

INFO

  • This mode requires a global 3d position estimate (from GPS or inferred from a local position).
  • The vehicle must be armed before this mode can be engaged.
  • This mode is automatic - no user intervention is required to control the vehicle.
  • RC control switches can be used to change flight modes on any vehicle.

Description

Missions are usually created in a ground control station (e.g. QGroundControl) and uploaded prior to launch. They may also be created by a developer API, and/or uploaded in flight.

Mission commands are handled in a way that is appropriate for each fixed-wing flight characteristics (for example loiter is implemented as flying in a circle).

INFO

Missions are uploaded onto a SD card that needs to be inserted before booting up the autopilot.

At high level all vehicle types behave in the same way when MISSION mode is engaged:

  1. If no mission is stored, or if PX4 has finished executing all mission commands, or if the mission is not feasible:

    • If flying the vehicle will loiter.
    • If landed the vehicle will "wait".
  2. If a mission is stored and PX4 is flying it will execute the mission/flight plan from the current step.

    • A takeoff mission item will be treated as a normal waypoint.
  3. If a mission is stored and the vehicle is landed it will only takeoff if the active waypoint is a Takeoff. If configured for catapult launch, the vehicle must also be launched (see FW Takeoff/Landing in Mission).

  4. If no mission is stored, or if PX4 has finished executing all mission commands:

    • If flying the vehicle will loiter.
    • If landed the vehicle will "wait".
  5. You can manually change the current mission command by selecting it in QGroundControl.

    INFO

    If you have a Jump to item command in the mission, moving to another item will not reset the loop counter. One implication is that if you change the current mission command to 1 this will not "fully restart" the mission.

:::

  1. The mission will only reset when the vehicle is disarmed or when a new mission is uploaded.

    TIP

    To automatically disarm the vehicle after it lands, in QGroundControl go to Vehicle Setup > Safety, navigate to Land Mode Settings and check the box labeled Disarm after. Enter the time to wait after landing before disarming the vehicle.

:::

Missions can be paused by switching out of mission mode to any other mode (such as Hold mode or Position mode), and resumed by switching back to mission mode. If the vehicle was not capturing images when it was paused, on resuming it will head from its current position towards the same waypoint as it as was heading towards originally. If the vehicle was capturing images (has camera trigger items) it will instead head from its current position towards the last waypoint it traveled through (before pausing), and then retrace its path at the same speed and with the same camera triggering behaviour. This ensures that in survey/camera missions the planned path is captured. A mission can be uploaded while the vehicle is paused, in which which case the current active mission item is set to 1.

INFO

When a mission is paused while the camera on the vehicle was triggering, PX4 sets the current active mission item to the previous waypoint, so that when the mission is restarted the vehicle will retrace its last mission leg. In addition, PX4 stores the last applied mission items for speed setting and camera triggering (from the already covered mission plan), and re-applies those settings on resuming the mission.

WARNING

Ensure that the throttle stick is non-zero before switching to any RC mode (otherwise the vehicle will crash). We recommend you centre the control sticks before switching to any other mode.

For more information about mission planning, see:

Mission Feasibility Checks

PX4 runs some basic sanity checks to determine if a mission is feasible when it is uploaded, and when the vehicle is first armed. If any of the checks fail, the user is notified and it is not possible to start the mission.

A subset of the most important checks are listed below:

  • First mission item too far away from vehicle (MIS_DIST_1WP)
  • Any mission item conflicts with a plan or safety geofence
  • More than one land start mission item defined (MAV_CMD_DO_LAND_START)
  • A fixed-wing landing has an infeasible slope angle (FW_LND_ANG)
  • Land start item (MAV_CMD_DO_LAND_START) appears in mission before an RTL item (MAV_CMD_NAV_RETURN_TO_LAUNCH)
  • Missing takeoff and/or land item when these are configured as a requirement (MIS_TKO_LAND_REQ)

QGroundControl Support

QGroundControl provides additional GCS-level mission handling support (in addition to that provided by the flight controller).

For more information see:

Mission Parameters

Mission behaviour is affected by a number of parameters, most of which are documented in Parameter Reference > Mission. A very small subset are listed below.

General parameters:

ParameterDescription
NAV_RCL_ACTRC loss failsafe mode (what the vehicle will do if it looses RC connection) - e.g. enter hold mode, return mode, terminate etc.
NAV_LOITER_RADFixed-wing loiter radius.

Parameters related to mission feasibility checks:

ParameterDescription
MIS_DIST_1WPThe mission will not be started if the current waypoint is more distant than this value from the home position. Disabled if value is 0 or less.
FW_LND_ANGMaximum landing slope angle.
MIS_TKO_LAND_REQMission takeoff/landing requirement configuration. FW and VTOL both have it set to 2 by default, which means that the mission has to contain a landing.

Mission Commands

PX4 "accepts" the following MAVLink mission commands in Mission mode (with some caveats, given after the list). Unless otherwise noted, the implementation is as defined in the MAVLink specification.

Mission Items:

GeoFence Definitions

Rally Points

INFO

Please add an issue report or PR if you find a missing/incorrect message. ::: info:

  • PX4 parses the above messages, but they are not necessary acted on. For example, some messages are vehicle-type specific.
  • PX4 does not support local frames for mission commands (e.g. MAV_FRAME_LOCAL_NED).
  • Not all messages/commands are exposed via QGroundControl.
  • The list may become out of date as messages are added. You can check the current set by inspecting the code. Support is MavlinkMissionManager::parse_mavlink_mission_item in /src/modules/mavlink/mavlink_mission.cpp.

Rounded turns: Inter-Waypoint Trajectory

PX4 expects to follow a straight line from the previous waypoint to the current target (it does not plan any other kind of path between waypoints - if you need one you can simulate this by adding additional waypoints).

The vehicle will follow a smooth rounded curve towards the next waypoint (if one is defined) defined by the acceptance radius (NAV_ACC_RAD). The diagram below shows the sorts of paths that you might expect.

acc-rad

Vehicles switch to the next waypoint as soon as they enter the acceptance radius. This is defined by the "L1 distance", which is is computed from two parameters: NPFG_DAMPING and NPFG_PERIOD, and the current ground speed. By default, it's about 70 meters.

The equation is:

L1distance=1πL1dampingL1periodvxyground

Mission Takeoff

Starting flights with mission takeoff (and landing using a mission landing) is the recommended way of operating a plane autonomously.

Both runway takeoff and hand-launched takeoff are supported — for configuration information see Takeoff mode (FW).

The takeoff behaviour is defined in a Takeoff mission item, which corresponds to the MAV_CMD_NAV_TAKEOFF MAVLink command. During mission execution the vehicle will takeoff towards this waypoint, and climb until the specified altitude is reached. The mission item is then accepted, and the mission will start executing the next item.

More specifically, the takeoff mission item defines the takeoff course and clearance altitude. The course is the line between the vehicle starting point and the horizontal position defined in the mission item, while the clearance altitude is the mission item altitude.

For a runway takeoff, the Takeoff mission item will cause the vehicle to arm, throttle up the motors and take off. When hand-launching the vehicle will arm, but only throttle up when the vehicle is thrown (the acceleration trigger is detected). In both cases, the vehicle should be placed (or launched) facing towards the takeoff waypoint when the mission is started. If possible, always make the vehicle takeoff into the wind.

INFO

A fixed-wing mission requires a Takeoff mission item to takeoff; if however the vehicle is already flying when the mission is started the takeoff item will be treated as a normal waypoint.

For more infomormation about takeoff behaviour and configuration see Takeoff mode (FW).

Mission Landing

Fixed-wing mission landing is the recommended way to land a plane autonomously. This can be planned in QGroundControl using fixed-wing landing pattern.

If possible, always plan the landing such that it does the approach into the wind.

The following sections describe the landing sequence, land abort and nudging, safety considerations, and configuration.

Landing Sequence

A landing pattern consists of a loiter waypoint (MAV_CMD_NAV_LOITER_TO_ALT) followed by a land waypoint (MAV_CMD_NAV_LAND). The positions of the two points define the start and end point of the landing approach, and hence the glide slope for the landing approach.

This pattern results in the following landing sequence:

  1. Fly to landing location: The aircraft flies at its current altitude towards the loiter waypoint.
  2. Descending orbit to approach altitude: On reaching the loiter radius of the waypoint, the vehicle performs a descending orbit until it reaches the "approach altitude" (the altitude of the loiter waypoint). The vehicle continues to orbit at this altitude until it has a tanjential path towards the land waypoint, at which point the landing approach is initiated.
  3. Landing approach: The aircraft follows the landing approach slope towards the land waypoint until the flare altitude is reached.
  4. Flare: The vehicle flares until it touches down.

Fixed-wing landing

Landing Approach

The vehicle tracks the landing slope (generally at a slower speed than cruise) until reaching the flare altitude.

Note that the glide slope is calculated from the 3D positions of the loiter and landing waypoints; if its angle exceeds the parameter FW_LND_ANG the mission will be rejected as unfeasible on upload.

The parameters that affect the landing approach are listed below.

ParameterDescription
FW_LND_ANGThe maximum achievable landing approach slope angle. Note that smaller angles may still be commanded via the landing pattern mission item.
FW_LND_EARLYCFGOptionally deploy landing configuration during the landing descent orbit (e.g. flaps, spoilers, landing airspeed).
FW_LND_AIRSPDCalibrated airspeed setpoint during landing.
FW_FLAPS_LND_SCLFlaps setting during landing.
FW_LND_THRTC_SCAltitude time constant factor for landing (overrides default TECS tuning).

Flaring / Roll-out

Flaring consists of a switch from altitude tracking to a shallow sink rate setpoint and constraints on the commandable throttle, resulting in nose up manuevering to slow the descent and produce a softer touchdown.

The flaring altitude is calculated during the final approach via "time-to-impact" (FW_LND_FL_TIME) and the approach descent rate. An additional safety parameter FW_LND_FLALT sets the minimum altitude at which the vehicle will flare (if the time based altitude is too low to allow a safe flare maneuver).

If belly landing, the vehicle will continue in the flaring state until touchdown, land detection, and subsequent disarm. For runway landings, FW_LND_TD_TIME enables setting the time post flare start to pitch down the nose (e.g. consider tricycle gear) onto the runway (RWTO_PSP) and avoid bouncing. This time roughly corresponds to the touchdown post flare, and should be tuned for a given airframe during test flights only after the flare has been tuned.

The parameters that affect flaring are listed below.

ParameterDescription
FW_LND_FL_TIMETime before impact (at current descent rate) at which the vehicle should flare.
FW_LND_FL_SINKA shallow sink rate the aircraft will track during the flare.
FW_LND_FLALTMinimum altitude above ground the aircraft must flare. This is only used when the time-based flare altitude is too low.
FW_LND_FL_PMAXMaximum allowed pitch during the flare.
FW_LND_FL_PMINMinimum allowed pitch during the flare (often necessary to avoid negative pitch angles commanded to increase airspeed, as the throttle is reduced to idle setting.)
FW_LND_TD_TIMEThe time after flare start when the vehicle should pitch the nose down.
RWTO_PSPPitch setpoint while on the runway. For tricycle gear, typically near zero. For tail draggers, positive.
FW_THR_IDLEIdle throttle setting. The vehicle will retain this setting throughout the flare and roll out.

Abort

Operator Abort

The landing may be aborted by the operator at any point during the final approach using the MAV_CMD_DO_GO_AROUND command. On QGroundControl a popup button appears during landing to enable this.

Aborting the landing results in a climb out to an orbit pattern centered above the land waypoint. The maximum of the aircraft's current altitude and MIS_LND_ABRT_ALT is set as the abort orbit altitude height relative to (above) the landing waypoint. Landing configuration (e.g. flaps, spoilers, landing airspeed) is disabled during abort and the aicraft flies in cruise conditions.

The abort command is disabled during the flare for safety. Operators may still manually abort the landing by switching to any manual mode, such as Stabilized mode), though it should be noted that this is risky!

Automatic Abort

Automatic abort logic is additionally available for several conditions, if configured. Available automatic abort criteria may be enabled via bitmask parameter FW_LND_ABORT. One example of an automatic abort criteria is the absence of a valid range measurement from a distance sensor.

WARNING

Landing without a distance sensor is strongly discouraged. Disabling terrain estimation with FW_LND_USETER and select bits of FW_LND_ABORT will remove the default distance sensor requirement, but consequently falls back to GNSS altitude to determine the flaring altitude, which may be several meters too high or too low, potentially resulting in damage to the airframe.

ParameterDescription
MIS_LND_ABRT_ALTThe minimum altitude above the land point an abort orbit can be commanded.
FW_LND_ABORTDetermines which automatic abort criteria are enabled.
FW_LND_USETEREnables use of the distance sensor during the final approach.

Nudging

In the case of minor GNSS or map discrepancies causing an offset approach, small manual adjustments to the landing approach and roll out can be made by the operator (via yaw stick) when FW_LND_NUDGE is enabled. Options include either nudging the approach angle or the full approach path.

In both cases, the vehicle remains in full auto mode, tracking the shifted approach vector. FW_LND_TD_OFF allows determination of how far to the left or right of the landing waypoint the projected touchdown point may be nudged. Yaw stick input corresponds to a nudge "rate". Once the stick is released (zero rate), the approach path or angle will stop moving.

Fixed-wing landing nudging

Approach path nudging is frozen once the flare starts. If conducting a runway landing with steerable nose wheel, the yaw stick command passes directly to the nose wheel from flare start, during roll out, until disarm. Note that if the wheel controller is enabled (FW_W_EN), the controller will actively attempt to steer the vehicle to the approach path, i.e. "fighting" operator yaw stick inputs.

INFO

Nudging should not be used to supplement poor position control tuning. If the vehicle is regularly showing poor tracking peformance on a defined path, please refer to the fixed-wing control tuning guide for instruction.

ParameterDescription
FW_LND_NUDGEEnable nudging behavior for fixed-wing landing.
FW_LND_TD_OFFConfigure the allowable touchdown lateral offset from the commanded landing point.
FW_W_ENEnable the nose wheel steering controller.

Near Ground Safety Constraints

In landing mode, the distance sensor is used to determine proximity to the ground, and the airframe's geometry is used to calculate roll contraints to prevent wing strike.

Fixed-wing landing nudging

ParameterDescription
FW_WING_SPANWing span of the airframe.
FW_WING_HEIGHTHeight of wing from bottom of gear (or belly if no gear).

See Also