Mission Mode
Last updated
Last updated
Mission mode causes the vehicle to execute a predefined autonomous (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 (QGC).
:::note
This mode requires a global 3d position estimate (from GPS or inferred from a ).
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.
RC stick movement in a multicopter (or VTOL in multicopter mode) will change the vehicle to unless handling a critical battery failsafe. :::
Missions are usually created in a ground control station (e.g. ) and uploaded prior to launch. They may also be created by a developer API, and/or uploaded in flight.
Individual are handled in a way that is appropriate for each vehicle's flight characteristics (for example loiter is implemented as hover for copter and circle for fixed-wing). VTOL vehicles follow the behavior and parameters of fixed-wing when in FW mode, and of copter when in MC mode.
:::note 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:
If no mission is stored, or if PX4 has finished executing all mission commands, or if the :
If flying the vehicle will loiter.
If landed the vehicle will "wait".
If a mission is stored and PX4 is flying it will execute the from the current step.
On copters PX4 will treat a takeoff item as a normal waypoint if already flying.
If a mission is stored and PX4 is landed:
On copters PX4 will execute the . If the mission does not have a TAKEOFF
command then PX4 will fly the vehicle to the minimum altitude before executing the remainder of the flight plan from the current step.
On fixed-wing vehicles PX4 will not automatically take off (the autopilot will detect the lack of movement and set the throttle to zero). If the currently active waypoint is a Takeoff, the system will automatically takeoff (see ).
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".
You can manually change the current mission command by selecting it in QGroundControl.
:::note 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. :::
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 , navigate to Land Mode Settings and check the box labeled Disarm after. Enter the time to wait after landing before disarming the vehicle. :::
:::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:
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:
Any mission item conflicts with a plan or safety geofence
QGroundControl provides additional GCS-level mission handling support (in addition to that provided by the flight controller).
For more information see:
General parameters:
RC loss failsafe mode (what the vehicle will do if it looses RC connection) - e.g. enter hold mode, return mode, terminate etc.
Fixed-wing loiter radius.
The 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.
Maximum landing slope angle.
Mission 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.
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.
Param3 (flythrough) is ignored. Flythrough is always enabled if param 1 (time_inside) > 0.
MAV_CMD_NAV_VTOL_TAKEOFF.param2
(transition heading) is ignored. Instead the heading to the next waypoint is used for the transition heading.
Note:
PX4 parses the above messages, but they are not necessary acted on. For example, some messages are vehicle-type specific.
Not all messages/commands are exposed via QGroundControl.
:::note Please add an issue report or PR if you find a missing/incorrect message. :::
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).
Vehicles switch to the next waypoint as soon as they enter the acceptance radius:
For FW the acceptance radius is defined by the "L1 distance".
By default, it's about 70 meters.
If a mission with no takeoff mission item is started, the vehicle will ascend to the minimum takeoff altitude and then proceed to the first Waypoint
mission item.
If the vehicle is already flying when the mission is started, a takeoff mission item is treated as a normal waypoint.
Starting flights with mission takeoff (and landing using a mission landing) is the recommended way of operating a plane autonomously.
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.
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.
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.
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.
This pattern results in the following landing sequence:
Fly to landing location: The aircraft flies at its current altitude towards the loiter waypoint.
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.
Landing approach: The aircraft follows the landing approach slope towards the land waypoint until the flare altitude is reached.
Flare: The vehicle flares until it touches down.
The vehicle tracks the landing slope (generally at a slower speed than cruise) until reaching the flare altitude.
The parameters that affect the landing approach are listed below.
The maximum achievable landing approach slope angle. Note that smaller angles may still be commanded via the landing pattern mission item.
Optionally deploy landing configuration during the landing descent orbit (e.g. flaps, spoilers, landing airspeed).
Calibrated airspeed setpoint during landing.
Flaps setting during landing.
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 parameters that affect flaring are listed below.
Time before impact (at current descent rate) at which the vehicle should flare.
A shallow sink rate the aircraft will track during the flare.
Minimum altitude above ground the aircraft must flare. This is only used when the time-based flare altitude is too low.
Maximum allowed pitch during the flare.
Minimum allowed pitch during the flare (often necessary to avoid negative pitch angles commanded to increase airspeed, as the throttle is reduced to idle setting.)
The time after flare start when the vehicle should pitch the nose down.
Pitch setpoint while on the runway. For tricycle gear, typically near zero. For tail draggers, positive.
Idle throttle setting. The vehicle will retain this setting throughout the flare and roll out.
The minimum altitude above the land point an abort orbit can be commanded.
Determines which automatic abort criteria are enabled.
Enables use of the distance sensor during the final approach.
Enable nudging behavior for fixed-wing landing.
Configure the allowable touchdown lateral offset from the commanded landing point.
Enable the nose wheel steering controller.
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.
Wing span of the airframe.
Height of wing from bottom of gear (or belly if no gear).
Plan a VTOL mission takeoff by adding a VTOL Takeoff
mission item to the map.
A VTOL mission requires a VTOL 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.
Missions can be paused by switching out of mission mode to any other mode (such as or . When you switch back to mission mode the vehicle will continue the mission, heading from the current vehicle position to the current active mission item (the same waypoint it as heading towards originally). Note that if you moved the vehicle while the mission was paused you will no longer be following the original track towards the waypoint. A mission can be uploaded while the vehicle is paused, in which which case the current active mission item is set to 1.
(QGroundControl User Guide)
First mission item too far away from vehicle ()
More than one land start mission item defined ()
A fixed-wing landing has an infeasible slope angle ()
Land start item (MAV_CMD_DO_LAND_START
) appears in mission before an RTL item ()
Missing takeoff and/or land item when these are configured as a requirement ()
Mission behaviour is affected by a number of parameters, most of which are documented in . A very small subset are listed below.
Controls whether stick movement on a multicopter (or VTOL in MC mode) gives control back to the pilot in . This can be separately enabled for auto modes and for offboard mode, and is enabled in auto modes by default.
The amount of stick movement that causes a transition to (if is enabled).
Parameters related to :
PX4 does not support local frames for mission commands (e.g. ).
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 .
MC vehicles will change the speed when approaching or leaving a waypoint based on the tuning. The vehicle will follow a smooth rounded curve towards the next waypoint (if one is defined) defined by the acceptance radius (). The diagram below shows the sorts of paths that you might expect.
For MC this radius is defined by .
The L1 distance is computed from two parameters: and , and the current ground speed.
The equation is:
Plan a multicopter mission takeoff by adding a Takeoff
mission item to the map (this corresponds to the MAVLink command).
During mission execution this will cause the vehicle to ascend vertically to the minimum takeoff altitude defined in the parameter, then head towards the 3D position defined in the mission item.
:::note A more detailed description of mission mode fixed-wing takeoff can be found in (covering fixed wing takeoff in both mission mode and takeoff mode). :::
Fixed-wing mission takeoffs are defined in a Takeoff mission item, which corresponds to the MAVLink command.
Both runway and hand-launched takeoff are supported — for configuration information see . 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).
Fixed wing mission landing is the recommended way to land a plane autonomously. This can be planned in QGroundControl using .
:::note Note fixed wing landing using is currently broken, so mission landing is the only way to autonomously land a plane. :::
A landing pattern consists of a loiter waypoint () followed by a land waypoint (). 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.
Note that the glide slope is calculated from the 3D positions of the loiter and landing waypoints; if its angle exceeds the parameter the mission will be rejected as unfeasible on upload.
Altitude time constant factor for landing (overrides default ).
The flaring altitude is calculated during the final approach via "time-to-impact" () and the approach descent rate. An additional safety parameter 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, enables setting the time post flare start to pitch down the nose (e.g. consider tricycle gear) onto the runway () 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 landing may be aborted by the operator at any point during the final approach using the 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 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 ), though it should be noted that this is risky!
Automatic abort logic is additionally available for several conditions, if configured. Available automatic abort criteria may be enabled via bitmask parameter . 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 and select bits of 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. :::
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 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. 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.
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 (), the controller will actively attempt to steer the vehicle to the approach path, i.e. "fighting" operator yaw stick inputs.
:::note 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 for instruction. :::
During mission execution the vehicle will ascend vertically to the minimum takeoff altitude defined in the parameter, then transition to fixed-wing mode with the heading defined in the mission item. After transitioning the vehicle heads towards the 3D position defined in the mission item.